diff --git a/photon-client/src/views/SettingsViews/General.vue b/photon-client/src/views/SettingsViews/General.vue
index 07e5322a5..064d9f121 100644
--- a/photon-client/src/views/SettingsViews/General.vue
+++ b/photon-client/src/views/SettingsViews/General.vue
@@ -2,8 +2,10 @@
Version: {{ settings.version }}
—
-
Hardware model: {{ settings.hardwareModel }}
- —
+
+ Hardware model: {{ settings.hardwareModel }}
+ —
+
Platform: {{ settings.hardwarePlatform }}
—
GPU Acceleration: {{ settings.gpuAcceleration ? "Enabled" : "Unsupported" }}{{ settings.gpuAcceleration ? " (" + settings.gpuAcceleration + " mode)" : "" }}
@@ -42,7 +44,7 @@
>
mdi-restart
@@ -55,7 +57,7 @@
>
mdi-restart
@@ -109,6 +111,12 @@ export default {
}
},
methods: {
+ restartProgram() {
+ this.axios.post('http://' + this.$address + '/api/restartProgram', {});
+ },
+ restartDevice() {
+ this.axios.post('http://' + this.$address + '/api/restartDevice', {});
+ },
readImportedSettings(event) {
let formData = new FormData();
formData.append("zipData", event.target.files[0]);
diff --git a/photon-client/src/views/SettingsViews/Networking.vue b/photon-client/src/views/SettingsViews/Networking.vue
index f4146eeb0..d92e1059e 100644
--- a/photon-client/src/views/SettingsViews/Networking.vue
+++ b/photon-client/src/views/SettingsViews/Networking.vue
@@ -12,7 +12,7 @@
/>
>();
+ var collectedSources = new HashMap();
var camConf2019 =
new CameraConfiguration("WPI2019", TestUtils.getTestMode2019ImagePath().toString());
@@ -115,8 +114,12 @@ public class Main {
var fvs2020 = new FileVisionSource(camConf2020);
- collectedSources.put(fvs2019, psList2019);
- collectedSources.put(fvs2020, psList2020);
+ var cfg2019 = new CameraConfiguration("2019", "2019");
+ cfg2019.pipelineSettings = psList2019;
+ var cfg2020 = new CameraConfiguration("2019", "2019");
+ cfg2020.pipelineSettings = psList2020;
+ collectedSources.put(fvs2019, cfg2019);
+ collectedSources.put(fvs2020, cfg2020);
// logger.info("Adding " + allSources.size() + " configs to VMM.");
VisionModuleManager.getInstance().addSources(collectedSources).forEach(VisionModule::start);
diff --git a/photon-server/src/main/java/org/photonvision/common/configuration/CameraConfiguration.java b/photon-server/src/main/java/org/photonvision/common/configuration/CameraConfiguration.java
index 544c70a91..7b1c381ac 100644
--- a/photon-server/src/main/java/org/photonvision/common/configuration/CameraConfiguration.java
+++ b/photon-server/src/main/java/org/photonvision/common/configuration/CameraConfiguration.java
@@ -49,7 +49,6 @@ public class CameraConfiguration {
public CameraType cameraType = CameraType.UsbCamera;
public double FOV = 70;
public final List calibrations;
- public List cameraLeds = new ArrayList<>();
public int currentPipelineIndex = 0;
public Rotation2d camPitch = new Rotation2d();
@@ -89,7 +88,6 @@ public class CameraConfiguration {
@JsonProperty("path") String path,
@JsonProperty("cameraType") CameraType cameraType,
@JsonProperty("calibration") List calibrations,
- @JsonProperty("cameraLEDs") List cameraLeds,
@JsonProperty("currentPipelineIndex") int currentPipelineIndex,
@JsonProperty("camPitch") Rotation2d camPitch) {
this.baseName = baseName;
@@ -99,7 +97,6 @@ public class CameraConfiguration {
this.path = path;
this.cameraType = cameraType;
this.calibrations = calibrations != null ? calibrations : new ArrayList<>();
- this.cameraLeds = cameraLeds;
this.currentPipelineIndex = currentPipelineIndex;
this.camPitch = camPitch;
diff --git a/photon-server/src/main/java/org/photonvision/common/configuration/ConfigManager.java b/photon-server/src/main/java/org/photonvision/common/configuration/ConfigManager.java
index 418486f4e..f2443d9eb 100644
--- a/photon-server/src/main/java/org/photonvision/common/configuration/ConfigManager.java
+++ b/photon-server/src/main/java/org/photonvision/common/configuration/ConfigManager.java
@@ -301,12 +301,8 @@ public class ConfigManager {
return loadedConfigurations;
}
- public void addCameraConfigurations(HashMap> sources) {
- List list =
- sources.keySet().stream()
- .map(it -> it.getSettables().getConfiguration())
- .collect(Collectors.toList());
- getConfig().addCameraConfigs(list);
+ public void addCameraConfigurations(HashMap sources) {
+ getConfig().addCameraConfigs(sources.values());
requestSave();
}
diff --git a/photon-server/src/main/java/org/photonvision/common/configuration/HardwareConfig.java b/photon-server/src/main/java/org/photonvision/common/configuration/HardwareConfig.java
index a20a5215a..45c91fce0 100644
--- a/photon-server/src/main/java/org/photonvision/common/configuration/HardwareConfig.java
+++ b/photon-server/src/main/java/org/photonvision/common/configuration/HardwareConfig.java
@@ -18,6 +18,8 @@
package org.photonvision.common.configuration;
import java.util.ArrayList;
+import java.util.Collections;
+import java.util.List;
public class HardwareConfig {
@@ -47,6 +49,7 @@ public class HardwareConfig {
// Device stuff
public final String restartHardwareCommand;
public final double vendorFOV; // -1 for unmanaged
+ public final List blacklistedResIndices; // this happens before the defaults are applied
public HardwareConfig() {
deviceName = "";
@@ -71,6 +74,7 @@ public class HardwareConfig {
restartHardwareCommand = "";
vendorFOV = -1;
+ blacklistedResIndices = Collections.emptyList();
}
@SuppressWarnings("unused")
@@ -94,7 +98,8 @@ public class HardwareConfig {
String gpuTempCommand,
String ramUtilCommand,
String restartHardwareCommand,
- double vendorFOV) {
+ double vendorFOV,
+ List blacklistedResIndices) {
this.deviceName = deviceName;
this.deviceLogoPath = deviceLogoPath;
this.supportURL = supportURL;
@@ -115,6 +120,7 @@ public class HardwareConfig {
this.ramUtilCommand = ramUtilCommand;
this.restartHardwareCommand = restartHardwareCommand;
this.vendorFOV = vendorFOV;
+ this.blacklistedResIndices = blacklistedResIndices;
}
public final boolean hasPresetFOV() {
diff --git a/photon-server/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java b/photon-server/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java
index 20444008f..4f0521763 100644
--- a/photon-server/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java
+++ b/photon-server/src/main/java/org/photonvision/common/configuration/PhotonConfiguration.java
@@ -17,11 +17,13 @@
package org.photonvision.common.configuration;
+import java.util.Collection;
import java.util.HashMap;
import java.util.List;
import java.util.Map;
import java.util.stream.Collectors;
import org.photonvision.PhotonVersion;
+import org.photonvision.common.hardware.Platform;
import org.photonvision.common.util.SerializationUtils;
import org.photonvision.vision.processes.VisionModule;
import org.photonvision.vision.processes.VisionModuleManager;
@@ -44,7 +46,7 @@ public class PhotonConfiguration {
return cameraConfigurations;
}
- public void addCameraConfigs(List config) {
+ public void addCameraConfigs(Collection config) {
for (var c : config) {
addCameraConfig(c);
}
@@ -95,8 +97,8 @@ public class PhotonConfiguration {
generalSubmap.put("version", PhotonVersion.versionString);
generalSubmap.put("gpuAcceleration", false); // TODO gpu accel and accel type
generalSubmap.put("gpuAccelerationType", "Unknown");
- generalSubmap.put("hardwareModel", "Unknown"); // TODO hardware model and platform
- generalSubmap.put("hardwarePlatform", "Unknown");
+ generalSubmap.put("hardwareModel", hardwareConfig.deviceName);
+ generalSubmap.put("hardwarePlatform", Platform.getCurrentPlatform().toString());
settingsSubmap.put("general", generalSubmap);
map.put("settings", settingsSubmap);
diff --git a/photon-server/src/main/java/org/photonvision/common/hardware/HardwareManager.java b/photon-server/src/main/java/org/photonvision/common/hardware/HardwareManager.java
index 5c1a888ff..d618ddfb7 100644
--- a/photon-server/src/main/java/org/photonvision/common/hardware/HardwareManager.java
+++ b/photon-server/src/main/java/org/photonvision/common/hardware/HardwareManager.java
@@ -19,14 +19,12 @@ package org.photonvision.common.hardware;
import edu.wpi.first.networktables.NetworkTableEntry;
import java.io.IOException;
-import java.util.HashMap;
import org.photonvision.common.ProgramStatus;
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.configuration.HardwareConfig;
import org.photonvision.common.dataflow.networktables.NTDataChangeListener;
import org.photonvision.common.dataflow.networktables.NetworkTablesManager;
import org.photonvision.common.hardware.GPIO.CustomGPIO;
-import org.photonvision.common.hardware.GPIO.GPIOBase;
import org.photonvision.common.hardware.VisionLED.VisionLEDMode;
import org.photonvision.common.hardware.metrics.MetricsBase;
import org.photonvision.common.logging.LogGroup;
@@ -36,13 +34,17 @@ import org.photonvision.common.util.ShellExec;
public class HardwareManager {
private static HardwareManager instance;
- private final HashMap VisionLEDs = new HashMap<>();
private final ShellExec shellExec = new ShellExec(true, false);
private final Logger logger = new Logger(HardwareManager.class, LogGroup.General);
private final HardwareConfig hardwareConfig;
+
+ @SuppressWarnings("FieldCanBeLocal")
private final StatusLED statusLED;
+
private final NetworkTableEntry ledModeEntry;
+
+ @SuppressWarnings("FieldCanBeLocal")
private final NTDataChangeListener ledModeListener;
public final VisionLED visionLED;
@@ -64,17 +66,34 @@ public class HardwareManager {
new VisionLED(
hardwareConfig.ledPins,
hardwareConfig.ledPWMFrequency,
- hardwareConfig.ledPWMRange.get(1));
+ (hardwareConfig.ledPWMRange != null && hardwareConfig.ledPWMRange.size() == 2)
+ ? hardwareConfig.ledPWMRange.get(1)
+ : 0);
ledModeEntry = NetworkTablesManager.getInstance().kRootTable.getEntry("ledMode");
ledModeEntry.setNumber(VisionLEDMode.VLM_DEFAULT.value);
ledModeListener = new NTDataChangeListener(ledModeEntry, visionLED::onLedModeChange);
+ Runtime.getRuntime().addShutdownHook(new Thread(this::onJvmExit));
+
// Start hardware metrics thread (Disabled until implemented)
// if (Platform.isLinux()) MetricsPublisher.getInstance().startTask();
}
+ private void onJvmExit() {
+ logger.info("Shutting down...");
+ visionLED.setState(false);
+ }
+
public boolean restartDevice() {
+ if (Platform.isRaspberryPi()) {
+ try {
+ return shellExec.executeBashCommand("reboot now") == 0;
+ } catch (IOException e) {
+ logger.error("Could not restart device!", e);
+ return false;
+ }
+ }
try {
return shellExec.executeBashCommand(hardwareConfig.restartHardwareCommand) == 0;
} catch (IOException e) {
diff --git a/photon-server/src/main/java/org/photonvision/common/hardware/Platform.java b/photon-server/src/main/java/org/photonvision/common/hardware/Platform.java
index 4a4f199be..2deb6de61 100644
--- a/photon-server/src/main/java/org/photonvision/common/hardware/Platform.java
+++ b/photon-server/src/main/java/org/photonvision/common/hardware/Platform.java
@@ -88,7 +88,7 @@ public enum Platform {
return false;
}
- private static Platform getCurrentPlatform() {
+ public static Platform getCurrentPlatform() {
if (RuntimeDetector.isWindows()) {
if (RuntimeDetector.is32BitIntel()) return WINDOWS_32;
if (RuntimeDetector.is64BitIntel()) return WINDOWS_64;
diff --git a/photon-server/src/main/java/org/photonvision/common/util/file/JacksonUtils.java b/photon-server/src/main/java/org/photonvision/common/util/file/JacksonUtils.java
index 9b49a0002..3241d6756 100644
--- a/photon-server/src/main/java/org/photonvision/common/util/file/JacksonUtils.java
+++ b/photon-server/src/main/java/org/photonvision/common/util/file/JacksonUtils.java
@@ -18,6 +18,7 @@
package org.photonvision.common.util.file;
import com.fasterxml.jackson.core.json.JsonReadFeature;
+import com.fasterxml.jackson.databind.DeserializationFeature;
import com.fasterxml.jackson.databind.ObjectMapper;
import com.fasterxml.jackson.databind.deser.std.StdDeserializer;
import com.fasterxml.jackson.databind.json.JsonMapper;
@@ -53,6 +54,7 @@ public class JacksonUtils {
ObjectMapper objectMapper =
JsonMapper.builder()
.configure(JsonReadFeature.ALLOW_JAVA_COMMENTS, true)
+ .configure(DeserializationFeature.FAIL_ON_UNKNOWN_PROPERTIES, false)
.activateDefaultTyping(ptv, ObjectMapper.DefaultTyping.JAVA_LANG_OBJECT)
.build();
File jsonFile = new File(path.toString());
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 6d8e454b9..9e87fa93c 100644
--- a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java
+++ b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java
@@ -36,6 +36,7 @@ import org.photonvision.common.hardware.Platform;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.common.networking.NetworkManager;
+import org.photonvision.common.util.ShellExec;
import org.photonvision.vision.processes.VisionModuleManager;
import org.photonvision.vision.target.TargetModel;
@@ -60,11 +61,7 @@ public class RequestHandler {
ctx.status(200);
logger.info("Settings uploaded, going down for restart.");
- if (!Platform.isRaspberryPi()) {
- logger.info("(On non-PI platforms, the program may not restart manually...)");
- }
-
- System.exit(0);
+ restartProgram(ctx);
} else {
logger.error("Couldn't read uploaded settings ZIP! Ignoring.");
ctx.status(500);
@@ -89,7 +86,6 @@ public class RequestHandler {
NetworkManager.getInstance().reinitialize();
NetworkTablesManager.getInstance().setConfig(networkConfig);
- logger.info("Responding to general settings with http 200");
context.status(200);
}
@@ -157,7 +153,17 @@ public class RequestHandler {
*/
public static void restartProgram(Context ctx) {
ctx.status(200);
- System.exit(0);
+
+ if (Platform.isRaspberryPi()) {
+ try {
+ new ShellExec().executeBashCommand("systemctl restart photonvision");
+ } catch (IOException e) {
+ logger.error("Could not restart device!", e);
+ System.exit(0);
+ }
+ } else {
+ System.exit(0);
+ }
}
public static void uploadPnpModel(Context ctx) {
diff --git a/photon-server/src/main/java/org/photonvision/server/SocketHandler.java b/photon-server/src/main/java/org/photonvision/server/SocketHandler.java
index 1d165544b..2f0e578d1 100644
--- a/photon-server/src/main/java/org/photonvision/server/SocketHandler.java
+++ b/photon-server/src/main/java/org/photonvision/server/SocketHandler.java
@@ -247,7 +247,7 @@ public class SocketHandler {
var changePipelineEvent =
new IncomingWebSocketEvent<>(
DataChangeDestination.DCD_ACTIVEMODULE,
- "startcalibration",
+ "startCalibration",
(Map) entryValue,
cameraIndex,
context);
diff --git a/photon-server/src/main/java/org/photonvision/vision/camera/FileVisionSource.java b/photon-server/src/main/java/org/photonvision/vision/camera/FileVisionSource.java
index ca8f02994..538cd6b9b 100644
--- a/photon-server/src/main/java/org/photonvision/vision/camera/FileVisionSource.java
+++ b/photon-server/src/main/java/org/photonvision/vision/camera/FileVisionSource.java
@@ -64,6 +64,11 @@ public class FileVisionSource implements VisionSource {
return settables;
}
+ @Override
+ public boolean isVendorCamera() {
+ return false;
+ }
+
private static class FileSourceSettables extends VisionSourceSettables {
private final VideoMode videoMode;
diff --git a/photon-server/src/main/java/org/photonvision/vision/camera/USBCameraSource.java b/photon-server/src/main/java/org/photonvision/vision/camera/USBCameraSource.java
index 5c9575976..4ce79fe53 100644
--- a/photon-server/src/main/java/org/photonvision/vision/camera/USBCameraSource.java
+++ b/photon-server/src/main/java/org/photonvision/vision/camera/USBCameraSource.java
@@ -23,7 +23,9 @@ import edu.wpi.cscore.VideoException;
import edu.wpi.cscore.VideoMode;
import edu.wpi.first.cameraserver.CameraServer;
import java.util.*;
+import java.util.stream.Collectors;
import org.photonvision.common.configuration.CameraConfiguration;
+import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.common.util.math.MathUtils;
@@ -141,7 +143,10 @@ public class USBCameraSource implements VisionSource {
videoModes = new HashMap<>();
List videoModesList = new ArrayList<>();
try {
- for (var videoMode : camera.enumerateVideoModes()) {
+ var modes = camera.enumerateVideoModes();
+ for (int i = 0; i < modes.length; i++) {
+ var videoMode = modes[i];
+
// Filter grey modes
if (videoMode.pixelFormat == VideoMode.PixelFormat.kGray
|| videoMode.pixelFormat == VideoMode.PixelFormat.kUnknown) {
@@ -156,19 +161,75 @@ public class USBCameraSource implements VisionSource {
}
videoModesList.add(videoMode);
+
+ // We look for modes with the same height/width/pixelformat as this mode
+ // and remove all the ones that are slower. This is sorted low to high.
+ // So we remove the last element (the fastest FPS) from the duplicate list,
+ // and remove all remaining elements from the final list
+ var duplicateModes =
+ videoModesList.stream()
+ .filter(
+ it ->
+ it.height == videoMode.height
+ && it.width == videoMode.width
+ && it.pixelFormat == videoMode.pixelFormat)
+ .sorted(Comparator.comparingDouble(it -> it.fps))
+ .collect(Collectors.toList());
+ duplicateModes.remove(duplicateModes.size() - 1);
+ videoModesList.removeAll(duplicateModes);
}
} catch (Exception e) {
logger.error("Exception while enumerating video modes!", e);
videoModesList = List.of();
}
- for (VideoMode videoMode : videoModesList) {
- videoModes.put(videoModesList.indexOf(videoMode), videoMode);
+
+ // Sort by resolution
+ var sortedList =
+ videoModesList.stream()
+ .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);
+ }
+
+ // Filter bogus modes on picam
+ if (cameraQuirks.hasQuirk(CameraQuirk.PiCam)) {
+ sortedList.removeIf(
+ it ->
+ (it.width == 1296
+ && it.height == 730
+ && it.pixelFormat == VideoMode.PixelFormat.kBGR)
+ || (it.width == 1296
+ && it.height == 972
+ && it.pixelFormat == VideoMode.PixelFormat.kBGR)
+ || (it.width == 2592
+ && it.height == 1944
+ && it.pixelFormat == VideoMode.PixelFormat.kBGR)
+ || (it.width == 160
+ && it.height == 120
+ && it.pixelFormat == VideoMode.PixelFormat.kBGR));
+ }
+
+ for (VideoMode videoMode : sortedList) {
+ videoModes.put(sortedList.indexOf(videoMode), videoMode);
}
}
return videoModes;
}
}
+ // TODO improve robustness of this detection
+ @Override
+ public boolean isVendorCamera() {
+ return ConfigManager.getInstance().getConfig().getHardwareConfig().hasPresetFOV()
+ && cameraQuirks.hasQuirk(CameraQuirk.PiCam);
+ }
+
@Override
public boolean equals(Object o) {
if (this == o) return true;
diff --git a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java
index 9bbeecb93..a6d004770 100644
--- a/photon-server/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java
+++ b/photon-server/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java
@@ -24,7 +24,7 @@ import org.photonvision.vision.pipe.CVPipe;
public class CalculateFPSPipe
extends CVPipe {
- private LinearFilter fpsFilter = LinearFilter.movingAverage(5);
+ private LinearFilter fpsFilter = LinearFilter.movingAverage(20);
StopWatch clock = new StopWatch();
@Override
diff --git a/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipeline.java b/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipeline.java
index b873244e7..88fea9be4 100644
--- a/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipeline.java
+++ b/photon-server/src/main/java/org/photonvision/vision/pipeline/CVPipeline.java
@@ -34,7 +34,10 @@ public abstract class CVPipeline userPipelines) {
+ public PipelineManager(
+ DriverModePipelineSettings driverSettings, List userPipelines) {
this.userPipelineSettings = new ArrayList<>(userPipelines);
+ // This is to respect the default res idx for vendor cameras
+
+ this.driverModePipeline.setSettings(driverSettings);
if (userPipelines.size() < 1) addPipeline(PipelineType.Reflective);
}
+ public PipelineManager(CameraConfiguration config) {
+ this(config.driveModeSettings, config.pipelineSettings);
+ }
+
/**
* Get the settings for a pipeline by index.
*
diff --git a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java
index 61ab42994..4a898138f 100644
--- a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java
+++ b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModule.java
@@ -171,10 +171,8 @@ public class VisionModule {
}
}
- // TODO improve robustness of this detection
private boolean isVendorCamera() {
- return ConfigManager.getInstance().getConfig().getHardwareConfig().hasPresetFOV()
- && cameraQuirks.hasQuirk(CameraQuirk.PiCam);
+ return visionSource.isVendorCamera();
}
public void startCalibration(UICalibrationData data) {
@@ -201,6 +199,8 @@ public class VisionModule {
var ret = pipelineManager.calibration3dPipeline.tryCalibration();
pipelineManager.setCalibrationMode(false);
+ setPipeline(pipelineManager.getCurrentPipelineIndex());
+
if (ret != null) {
logger.debug("Saving calibration...");
visionSource.getSettables().getConfiguration().addCalibration(ret);
diff --git a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java
index 5c0a7e46c..4c2653d9e 100644
--- a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java
+++ b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java
@@ -100,7 +100,7 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber {
parentModule.setPipeline(index);
parentModule.saveAndBroadcastAll();
return;
- case "startcalibration":
+ case "startCalibration":
var data = UICalibrationData.fromMap((Map) newPropValue);
parentModule.startCalibration(data);
parentModule.saveAndBroadcastAll();
diff --git a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java
index 4b567751f..0225c24a8 100644
--- a/photon-server/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java
+++ b/photon-server/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java
@@ -20,7 +20,7 @@ package org.photonvision.vision.processes;
import java.util.ArrayList;
import java.util.HashMap;
import java.util.List;
-import org.photonvision.vision.pipeline.CVPipelineSettings;
+import org.photonvision.common.configuration.CameraConfiguration;
/** VisionModuleManager has many VisionModules, and provides camera configuration data to them. */
public class VisionModuleManager {
@@ -52,8 +52,7 @@ public class VisionModuleManager {
return visionModules.get(i);
}
- public List addSources(
- HashMap> visionSources) {
+ public List addSources(HashMap visionSources) {
var addedModules = new ArrayList();
for (var entry : visionSources.entrySet()) {
var visionSource = entry.getKey();
diff --git a/photon-server/src/main/java/org/photonvision/vision/processes/VisionSource.java b/photon-server/src/main/java/org/photonvision/vision/processes/VisionSource.java
index 9b3023e66..47de565db 100644
--- a/photon-server/src/main/java/org/photonvision/vision/processes/VisionSource.java
+++ b/photon-server/src/main/java/org/photonvision/vision/processes/VisionSource.java
@@ -23,4 +23,6 @@ public interface VisionSource {
FrameProvider getFrameProvider();
VisionSourceSettables getSettables();
+
+ boolean isVendorCamera();
}
diff --git a/photon-server/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java b/photon-server/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java
index d4ef9bfbd..65fd582b2 100644
--- a/photon-server/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java
+++ b/photon-server/src/main/java/org/photonvision/vision/processes/VisionSourceManager.java
@@ -31,7 +31,6 @@ import org.photonvision.common.logging.Logger;
import org.photonvision.common.util.TimedTaskManager;
import org.photonvision.vision.camera.CameraType;
import org.photonvision.vision.camera.USBCameraSource;
-import org.photonvision.vision.pipeline.CVPipelineSettings;
public class VisionSourceManager {
@@ -87,7 +86,7 @@ public class VisionSourceManager {
"fullsettings", ConfigManager.getInstance().getConfig().toHashMap()));
}
- protected HashMap> tryMatchUSBCamImpl() {
+ protected HashMap tryMatchUSBCamImpl() {
// Detect cameras using CSCore
List connectedCameras =
new ArrayList<>(filterAllowedDevices(cameraInfoSupplier.get()));
@@ -154,10 +153,10 @@ public class VisionSourceManager {
var sources = loadVisionSourcesFromCamConfigs(matchedCameras);
// These sources can be turned into USB cameras, which can be added to the config manager
- var visionSourceMap = new HashMap>();
+ var visionSourceMap = new HashMap();
for (var src : sources) {
var usbSrc = (USBCameraSource) src;
- visionSourceMap.put(usbSrc, usbSrc.configuration.pipelineSettings);
+ visionSourceMap.put(usbSrc, usbSrc.configuration);
logger.debug(
() ->
"Matched config for camera \""
diff --git a/photon-server/src/test/java/org/photonvision/common/configuration/ConfigTest.java b/photon-server/src/test/java/org/photonvision/common/configuration/ConfigTest.java
index 9e353c953..631e89a7b 100644
--- a/photon-server/src/test/java/org/photonvision/common/configuration/ConfigTest.java
+++ b/photon-server/src/test/java/org/photonvision/common/configuration/ConfigTest.java
@@ -18,6 +18,7 @@
package org.photonvision.common.configuration;
import java.io.File;
+import java.io.FileWriter;
import java.io.IOException;
import java.nio.file.Files;
import java.nio.file.Path;
@@ -28,6 +29,7 @@ import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.LogLevel;
import org.photonvision.common.logging.Logger;
import org.photonvision.common.util.TestUtils;
+import org.photonvision.common.util.file.JacksonUtils;
import org.photonvision.vision.pipeline.ColoredShapePipelineSettings;
import org.photonvision.vision.pipeline.ReflectivePipelineSettings;
import org.photonvision.vision.target.TargetModel;
@@ -116,4 +118,16 @@ public class ConfigTest {
FileUtils.cleanDirectory(configMgr.configDirectoryFile);
configMgr.configDirectoryFile.delete();
}
+
+ @Test
+ public void testJacksonHandlesOldVersions() 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\":[], \"cameraLEDs\":[]}";
+ var writer = new FileWriter("test.json");
+ writer.write(str);
+ writer.flush();
+ writer.close();
+ Assertions.assertDoesNotThrow(
+ () -> JacksonUtils.deserialize(Path.of("test.json"), CameraConfiguration.class));
+ }
}
diff --git a/photon-server/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java b/photon-server/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java
index 15e30989d..7879cb0df 100644
--- a/photon-server/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java
+++ b/photon-server/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java
@@ -20,7 +20,6 @@ package org.photonvision.vision.processes;
import edu.wpi.cscore.VideoMode;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import java.util.HashMap;
-import java.util.List;
import org.junit.jupiter.api.*;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.configuration.ConfigManager;
@@ -29,7 +28,6 @@ import org.photonvision.common.util.TestUtils;
import org.photonvision.vision.frame.FrameProvider;
import org.photonvision.vision.frame.FrameStaticProperties;
import org.photonvision.vision.frame.provider.FileFrameProvider;
-import org.photonvision.vision.pipeline.CVPipelineSettings;
import org.photonvision.vision.pipeline.result.CVPipelineResult;
public class VisionModuleManagerTest {
@@ -57,6 +55,11 @@ public class VisionModuleManagerTest {
public VisionSourceSettables getSettables() {
return new TestSettables(new CameraConfiguration("", "", "", ""));
}
+
+ @Override
+ public boolean isVendorCamera() {
+ return false;
+ }
}
private static class TestSettables extends VisionSourceSettables {
@@ -105,14 +108,14 @@ public class VisionModuleManagerTest {
@Test
public void setupManager() {
ConfigManager.getInstance().load();
- var sources = new HashMap>();
+ var sources = new HashMap();
sources.put(
new TestSource(
new FileFrameProvider(
TestUtils.getWPIImagePath(
TestUtils.WPI2019Image.kCargoStraightDark72in_HighRes, false),
TestUtils.WPI2019Image.FOV)),
- List.of());
+ new CameraConfiguration("Foo", "Barr"));
var modules = VisionModuleManager.getInstance().addSources(sources);
var module0DataConsumer = new TestDataConsumer();
@@ -121,7 +124,7 @@ public class VisionModuleManagerTest {
modules.forEach(VisionModule::start);
- sleep(500);
+ sleep(1500);
Assertions.assertNotNull(module0DataConsumer.result);
printTestResults(module0DataConsumer.result);
diff --git a/photon-server/src/test/java/org/photonvision/vision/processes/VisionSourceManagerTest.java b/photon-server/src/test/java/org/photonvision/vision/processes/VisionSourceManagerTest.java
index d97b0214a..75f1d984c 100644
--- a/photon-server/src/test/java/org/photonvision/vision/processes/VisionSourceManagerTest.java
+++ b/photon-server/src/test/java/org/photonvision/vision/processes/VisionSourceManagerTest.java
@@ -25,6 +25,7 @@ import java.util.ArrayList;
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.util.TestUtils;
public class VisionSourceManagerTest {
@@ -38,6 +39,7 @@ public class VisionSourceManagerTest {
var inst = new VisionSourceManager();
var infoList = new ArrayList();
inst.cameraInfoSupplier = () -> infoList;
+ ConfigManager.getInstance().load();
inst.tryMatchUSBCamImpl();
var config = new CameraConfiguration("secondTestVideo", "dev/video1");