mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
Fix driver mode settings, sort resolutions (#115)
* Fix DriverMode settings * Update FileVisionSource.java * Sort modes by resolution * Filter duplicated modes * run spotless * Fix calibration bug * run format * aaaaa * Add hardware and platform support * decrease timing sensitivity * Better handle jvm exitg * Make reboot happen immediately * Cleanup restart * Remove debug print * Fix Jackson exploding when deserializing old versions of configs * Add unit test for old config versions * Run format * Add a comment * remove isvendorcam from pipeline manager * oops
This commit is contained in:
@@ -20,7 +20,6 @@ package org.photonvision;
|
||||
import edu.wpi.cscore.CameraServerCvJNI;
|
||||
import java.util.ArrayList;
|
||||
import java.util.HashMap;
|
||||
import java.util.List;
|
||||
import org.apache.commons.cli.*;
|
||||
import org.photonvision.common.configuration.CameraConfiguration;
|
||||
import org.photonvision.common.configuration.ConfigManager;
|
||||
@@ -84,7 +83,7 @@ public class Main {
|
||||
}
|
||||
|
||||
private static void addTestModeSources() {
|
||||
var collectedSources = new HashMap<VisionSource, List<CVPipelineSettings>>();
|
||||
var collectedSources = new HashMap<VisionSource, CameraConfiguration>();
|
||||
|
||||
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);
|
||||
|
||||
@@ -49,7 +49,6 @@ public class CameraConfiguration {
|
||||
public CameraType cameraType = CameraType.UsbCamera;
|
||||
public double FOV = 70;
|
||||
public final List<CameraCalibrationCoefficients> calibrations;
|
||||
public List<Integer> 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<CameraCalibrationCoefficients> calibrations,
|
||||
@JsonProperty("cameraLEDs") List<Integer> 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;
|
||||
|
||||
|
||||
@@ -301,12 +301,8 @@ public class ConfigManager {
|
||||
return loadedConfigurations;
|
||||
}
|
||||
|
||||
public void addCameraConfigurations(HashMap<VisionSource, List<CVPipelineSettings>> sources) {
|
||||
List<CameraConfiguration> list =
|
||||
sources.keySet().stream()
|
||||
.map(it -> it.getSettables().getConfiguration())
|
||||
.collect(Collectors.toList());
|
||||
getConfig().addCameraConfigs(list);
|
||||
public void addCameraConfigurations(HashMap<VisionSource, CameraConfiguration> sources) {
|
||||
getConfig().addCameraConfigs(sources.values());
|
||||
requestSave();
|
||||
}
|
||||
|
||||
|
||||
@@ -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<Integer> 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<Integer> 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() {
|
||||
|
||||
@@ -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<CameraConfiguration> config) {
|
||||
public void addCameraConfigs(Collection<CameraConfiguration> 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);
|
||||
|
||||
@@ -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<Integer, GPIOBase> 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) {
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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());
|
||||
|
||||
@@ -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) {
|
||||
|
||||
@@ -247,7 +247,7 @@ public class SocketHandler {
|
||||
var changePipelineEvent =
|
||||
new IncomingWebSocketEvent<>(
|
||||
DataChangeDestination.DCD_ACTIVEMODULE,
|
||||
"startcalibration",
|
||||
"startCalibration",
|
||||
(Map) entryValue,
|
||||
cameraIndex,
|
||||
context);
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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<VideoMode> 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;
|
||||
|
||||
@@ -24,7 +24,7 @@ import org.photonvision.vision.pipe.CVPipe;
|
||||
public class CalculateFPSPipe
|
||||
extends CVPipe<Void, Integer, CalculateFPSPipe.CalculateFPSPipeParams> {
|
||||
|
||||
private LinearFilter fpsFilter = LinearFilter.movingAverage(5);
|
||||
private LinearFilter fpsFilter = LinearFilter.movingAverage(20);
|
||||
StopWatch clock = new StopWatch();
|
||||
|
||||
@Override
|
||||
|
||||
@@ -34,7 +34,10 @@ public abstract class CVPipeline<R extends CVPipelineResult, S extends CVPipelin
|
||||
return settings;
|
||||
}
|
||||
|
||||
// TODO (BANKS) ACTUALLY SET THE CAMERA RESOLUTION
|
||||
public void setSettings(S s) {
|
||||
this.settings = s;
|
||||
}
|
||||
|
||||
public R run(Frame frame) {
|
||||
long pipelineStartNanos = System.nanoTime();
|
||||
|
||||
|
||||
@@ -20,6 +20,7 @@ package org.photonvision.vision.processes;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Comparator;
|
||||
import java.util.List;
|
||||
import org.photonvision.common.configuration.CameraConfiguration;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.vision.pipeline.*;
|
||||
@@ -54,12 +55,20 @@ public class PipelineManager {
|
||||
*
|
||||
* @param userPipelines Pipelines to add to the manager.
|
||||
*/
|
||||
public PipelineManager(List<CVPipelineSettings> userPipelines) {
|
||||
public PipelineManager(
|
||||
DriverModePipelineSettings driverSettings, List<CVPipelineSettings> 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.
|
||||
*
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -100,7 +100,7 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber {
|
||||
parentModule.setPipeline(index);
|
||||
parentModule.saveAndBroadcastAll();
|
||||
return;
|
||||
case "startcalibration":
|
||||
case "startCalibration":
|
||||
var data = UICalibrationData.fromMap((Map<String, Object>) newPropValue);
|
||||
parentModule.startCalibration(data);
|
||||
parentModule.saveAndBroadcastAll();
|
||||
|
||||
@@ -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<VisionModule> addSources(
|
||||
HashMap<VisionSource, List<CVPipelineSettings>> visionSources) {
|
||||
public List<VisionModule> addSources(HashMap<VisionSource, CameraConfiguration> visionSources) {
|
||||
var addedModules = new ArrayList<VisionModule>();
|
||||
for (var entry : visionSources.entrySet()) {
|
||||
var visionSource = entry.getKey();
|
||||
|
||||
@@ -23,4 +23,6 @@ public interface VisionSource {
|
||||
FrameProvider getFrameProvider();
|
||||
|
||||
VisionSourceSettables getSettables();
|
||||
|
||||
boolean isVendorCamera();
|
||||
}
|
||||
|
||||
@@ -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<VisionSource, List<CVPipelineSettings>> tryMatchUSBCamImpl() {
|
||||
protected HashMap<VisionSource, CameraConfiguration> tryMatchUSBCamImpl() {
|
||||
// Detect cameras using CSCore
|
||||
List<UsbCameraInfo> 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<VisionSource, List<CVPipelineSettings>>();
|
||||
var visionSourceMap = new HashMap<VisionSource, CameraConfiguration>();
|
||||
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 \""
|
||||
|
||||
Reference in New Issue
Block a user