mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
UI now partially running, but errors still getting thrown
This commit is contained in:
@@ -1,5 +1,6 @@
|
||||
package com.chameleonvision.util;
|
||||
|
||||
import edu.wpi.cscore.VideoMode;
|
||||
import org.opencv.core.Scalar;
|
||||
|
||||
import java.awt.*;
|
||||
@@ -11,4 +12,7 @@ public class Helpers {
|
||||
return new Scalar(color.getRed(), color.getGreen(), color.getBlue());
|
||||
}
|
||||
|
||||
public static String VideoModeToString(VideoMode videoMode) {
|
||||
return String.format("%dx%d@%dFPS in %s", videoMode.width, videoMode.height, videoMode.fps, videoMode.pixelFormat.toString());
|
||||
}
|
||||
}
|
||||
|
||||
@@ -2,13 +2,14 @@ package com.chameleonvision.vision;
|
||||
|
||||
import com.chameleonvision.config.CameraConfig;
|
||||
import com.chameleonvision.config.ConfigManager;
|
||||
import com.chameleonvision.util.Helpers;
|
||||
import com.chameleonvision.util.Platform;
|
||||
import com.chameleonvision.vision.camera.CameraProcess;
|
||||
import com.chameleonvision.vision.camera.USBCameraProcess;
|
||||
import com.chameleonvision.vision.pipeline.CVPipelineSettings;
|
||||
import com.chameleonvision.web.ServerHandler;
|
||||
import edu.wpi.cscore.UsbCamera;
|
||||
import edu.wpi.cscore.UsbCameraInfo;
|
||||
import org.apache.commons.lang3.tuple.Pair;
|
||||
import org.opencv.videoio.VideoCapture;
|
||||
|
||||
import java.io.IOException;
|
||||
@@ -21,7 +22,19 @@ public class VisionManager {
|
||||
|
||||
private static final LinkedHashMap<String, UsbCameraInfo> UsbCameraInfosByCameraName = new LinkedHashMap<>();
|
||||
private static final LinkedList<CameraConfig> LoadedCameraConfigs = new LinkedList<>();
|
||||
private static final LinkedHashMap<Integer, Pair<VisionProcess, String>> VisionProcessesByIndex = new LinkedHashMap<>();
|
||||
private static final LinkedList<VisionProcessManageable> VisionProcesses = new LinkedList<>();
|
||||
|
||||
private static class VisionProcessManageable {
|
||||
public final int index;
|
||||
public final String name;
|
||||
public final VisionProcess visionProcess;
|
||||
|
||||
public VisionProcessManageable(int index, String name, VisionProcess visionProcess) {
|
||||
this.index = index;
|
||||
this.name = name;
|
||||
this.visionProcess = visionProcess;
|
||||
}
|
||||
}
|
||||
|
||||
private static VisionProcess currentUIVisionProcess;
|
||||
|
||||
@@ -76,16 +89,17 @@ public class VisionManager {
|
||||
CameraConfig config = LoadedCameraConfigs.get(i);
|
||||
CameraProcess camera = new USBCameraProcess(config);
|
||||
VisionProcess process = new VisionProcess(camera, config.name);
|
||||
VisionProcessesByIndex.put(i, Pair.of(process, config.name));
|
||||
VisionProcesses.add(new VisionProcessManageable(i, config.name, process));
|
||||
}
|
||||
currentUIVisionProcess = VisionProcessesByIndex.get(0).getLeft();
|
||||
currentUIVisionProcess = getVisionProcessByIndex(0);
|
||||
return true;
|
||||
}
|
||||
|
||||
public static void startProcesses() {
|
||||
VisionProcessesByIndex.forEach((index, processNamePair) -> {
|
||||
processNamePair.getLeft().start();
|
||||
VisionProcesses.forEach((vpm) -> {
|
||||
vpm.visionProcess.start();
|
||||
});
|
||||
ServerHandler.sendFullSettings();
|
||||
}
|
||||
|
||||
public static VisionProcess getCurrentUIVisionProcess() {
|
||||
@@ -93,32 +107,38 @@ public class VisionManager {
|
||||
}
|
||||
|
||||
public static void setCurrentProcessByIndex(int processIndex) {
|
||||
if (processIndex > VisionProcessesByIndex.size() - 1) {
|
||||
if (processIndex > VisionProcesses.size() - 1) {
|
||||
return;
|
||||
}
|
||||
|
||||
currentUIVisionProcess = VisionProcessesByIndex.get(processIndex).getLeft();
|
||||
currentUIVisionProcess = getVisionProcessByIndex(0);
|
||||
}
|
||||
|
||||
public static VisionProcess getVisionProcessByIndex(int processIndex) {
|
||||
if (processIndex > VisionProcessesByIndex.size() - 1) {
|
||||
if (processIndex > VisionProcesses.size() - 1) {
|
||||
return null;
|
||||
}
|
||||
|
||||
return VisionProcessesByIndex.get(0).getLeft();
|
||||
VisionProcessManageable vpm = VisionProcesses.stream().filter(manageable -> manageable.index == processIndex).findFirst().orElse(null);
|
||||
return vpm != null ? vpm.visionProcess : null;
|
||||
}
|
||||
|
||||
public static List<String> getAllCameraNicknames() {
|
||||
return VisionProcessesByIndex.values().stream().map(processNamePair -> processNamePair.getLeft().getCamera().getProperties().getNickname()).collect(Collectors.toList());
|
||||
return VisionProcesses.stream().map(vpm -> vpm.visionProcess.getCamera()
|
||||
.getProperties().getNickname()).collect(Collectors.toList());
|
||||
}
|
||||
|
||||
public static List<String> getCurrentCameraPipelineNicknames() {
|
||||
return currentUIVisionProcess.getPipelines().stream().map(cvPipeline -> cvPipeline.settings.nickname).collect(Collectors.toList());
|
||||
}
|
||||
|
||||
public static void saveCameras() {
|
||||
VisionProcessesByIndex.forEach((index, process) -> {
|
||||
VisionProcess p = process.getLeft();
|
||||
String cameraName = process.getRight();
|
||||
List<CVPipelineSettings> pipelines = p.getPipelines().stream().map(cvPipeline -> cvPipeline.settings).collect(Collectors.toList());
|
||||
CVPipelineSettings driverMode = p.getDriverModeSettings();
|
||||
CameraConfig config = CameraConfig.fromUSBCameraProcess((USBCameraProcess) p.getCamera());
|
||||
VisionProcesses.forEach((vpm) -> {
|
||||
VisionProcess process = vpm.visionProcess;
|
||||
String cameraName = process.getCamera().getProperties().name;
|
||||
List<CVPipelineSettings> pipelines = process.getPipelines().stream().map(cvPipeline -> cvPipeline.settings).collect(Collectors.toList());
|
||||
CVPipelineSettings driverMode = process.getDriverModeSettings();
|
||||
CameraConfig config = CameraConfig.fromUSBCameraProcess((USBCameraProcess) process.getCamera());
|
||||
try {
|
||||
ConfigManager.saveCameraPipelines(cameraName, pipelines);
|
||||
ConfigManager.saveCameraDriverMode(cameraName, driverMode);
|
||||
@@ -128,4 +148,13 @@ public class VisionManager {
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
public static List<String> getCurrentCameraResolutionList() {
|
||||
return currentUIVisionProcess.getCamera().getProperties().getVideoModes().stream().map(Helpers::VideoModeToString).collect(Collectors.toList());
|
||||
}
|
||||
|
||||
public static int getCurrentUIVisionProcessIndex() {
|
||||
VisionProcessManageable vpm = VisionProcesses.stream().filter(v -> v.visionProcess == currentUIVisionProcess).findFirst().orElse(null);
|
||||
return vpm != null ? vpm.index : -1;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -57,7 +57,7 @@ public class VisionProcess {
|
||||
this.cameraProcess = cameraProcess;
|
||||
|
||||
pipelines.add(new CVPipeline2d("New Pipeline"));
|
||||
setPipeline(0);
|
||||
setPipeline(0, false);
|
||||
|
||||
// Thread to grab frames from the camera
|
||||
// TODO: (HIGH) fix video modes!!!
|
||||
@@ -125,7 +125,7 @@ public class VisionProcess {
|
||||
if (driverMode) {
|
||||
setPipelineInternal(driverModePipeline);
|
||||
} else {
|
||||
setPipeline(currentPipelineIndex);
|
||||
setPipeline(currentPipelineIndex, true);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -140,11 +140,11 @@ public class VisionProcess {
|
||||
ntPipelineEntry.setNumber(currentPipelineIndex);
|
||||
} else {
|
||||
currentPipelineIndex = wantedPipelineIndex;
|
||||
setPipeline(wantedPipelineIndex);
|
||||
setPipeline(wantedPipelineIndex, true);
|
||||
}
|
||||
}
|
||||
|
||||
public void setPipeline(int pipelineIndex) {
|
||||
public void setPipeline(int pipelineIndex, boolean updateUI) {
|
||||
CVPipeline newPipeline = pipelines.get(pipelineIndex);
|
||||
if (newPipeline != null) {
|
||||
setPipelineInternal(newPipeline);
|
||||
@@ -153,10 +153,13 @@ public class VisionProcess {
|
||||
// update the configManager
|
||||
if(ConfigManager.settings.currentCamera.equals(cameraProcess.getProperties().name)) {
|
||||
ConfigManager.settings.currentPipeline = pipelineIndex;
|
||||
HashMap<String, Object> pipeChange = new HashMap<>();
|
||||
pipeChange.put("currentPipeline", pipelineIndex);
|
||||
ServerHandler.broadcastMessage(pipeChange);
|
||||
ServerHandler.sendFullSettings();
|
||||
|
||||
if (updateUI) {
|
||||
HashMap<String, Object> pipeChange = new HashMap<>();
|
||||
pipeChange.put("currentPipeline", pipelineIndex);
|
||||
ServerHandler.broadcastMessage(pipeChange);
|
||||
ServerHandler.sendFullSettings();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -3,6 +3,7 @@ package com.chameleonvision.vision.camera;
|
||||
import com.chameleonvision.vision.enums.StreamDivisor;
|
||||
import com.chameleonvision.web.ServerHandler;
|
||||
import edu.wpi.cscore.CvSource;
|
||||
import edu.wpi.cscore.MjpegServer;
|
||||
import edu.wpi.cscore.VideoMode;
|
||||
import edu.wpi.first.cameraserver.CameraServer;
|
||||
import org.opencv.core.CvType;
|
||||
@@ -22,10 +23,10 @@ public class CameraStreamer {
|
||||
this.cvSource = CameraServer.getInstance().putVideo(name,
|
||||
cameraProcess.getProperties().staticProperties.imageWidth / divisor.value,
|
||||
cameraProcess.getProperties().staticProperties.imageHeight / divisor.value);
|
||||
setDivisor(divisor);
|
||||
setDivisor(divisor, false);
|
||||
}
|
||||
|
||||
public void setDivisor(StreamDivisor newDivisor) {
|
||||
public void setDivisor(StreamDivisor newDivisor, boolean updateUI) {
|
||||
this.divisor = newDivisor;
|
||||
var camValues = cameraProcess.getProperties();
|
||||
var newWidth = camValues.staticProperties.imageWidth / newDivisor.value;
|
||||
@@ -36,7 +37,9 @@ public class CameraStreamer {
|
||||
cameraProcess.getProperties().staticProperties.imageWidth / divisor.value,
|
||||
cameraProcess.getProperties().staticProperties.imageHeight / divisor.value);
|
||||
}
|
||||
ServerHandler.sendFullSettings();
|
||||
if (updateUI) {
|
||||
ServerHandler.sendFullSettings();
|
||||
}
|
||||
}
|
||||
|
||||
public StreamDivisor getDivisor() {
|
||||
@@ -46,7 +49,12 @@ public class CameraStreamer {
|
||||
public void setNewVideoMode(VideoMode newVideoMode) {
|
||||
// Trick to update cvSource and streamBuffer to the new resolution
|
||||
// Must change the cameraProcess resolution first
|
||||
setDivisor(divisor);
|
||||
setDivisor(divisor, true);
|
||||
}
|
||||
|
||||
public int getStreamPort() {
|
||||
var s = (MjpegServer) CameraServer.getInstance().getServer("serve_" + name);
|
||||
return s.getPort();
|
||||
}
|
||||
|
||||
public void runStream(Mat image) {
|
||||
|
||||
@@ -98,4 +98,8 @@ public class USBCameraProperties {
|
||||
public double calculateYaw(double PixelX, double centerX) {
|
||||
return FastMath.toDegrees(FastMath.atan((PixelX - centerX) / staticProperties.horizontalFocalLength));
|
||||
}
|
||||
|
||||
public List<VideoMode> getVideoModes() {
|
||||
return videoModes;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -2,8 +2,6 @@ package com.chameleonvision.vision.pipeline.pipes;
|
||||
|
||||
import org.apache.commons.lang3.tuple.Pair;
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.core.Size;
|
||||
import org.opencv.imgproc.Imgproc;
|
||||
|
||||
public class BlurPipe implements Pipe<Mat, Mat> {
|
||||
|
||||
@@ -19,9 +17,9 @@ public class BlurPipe implements Pipe<Mat, Mat> {
|
||||
public Pair<Mat, Long> run(Mat input) {
|
||||
long processStartNanos = System.nanoTime();
|
||||
|
||||
if (blurSize > 0) {
|
||||
Imgproc.blur(outputMat, outputMat, new Size(blurSize, blurSize));
|
||||
}
|
||||
// if (blurSize > 0) {
|
||||
// Imgproc.blur(outputMat, outputMat, new Size(blurSize, blurSize));
|
||||
// }
|
||||
|
||||
long processTime = processStartNanos - System.nanoTime();
|
||||
Pair<Mat, Long> output = Pair.of(outputMat, processTime);
|
||||
|
||||
@@ -59,13 +59,11 @@ public class ServerHandler {
|
||||
break;
|
||||
}
|
||||
case "driverMode": {
|
||||
for (HashMap.Entry<String, Object> e : data.entrySet()) {
|
||||
setField(VisionManager.getCurrentUIVisionProcess(), e.getKey(), e.getValue());
|
||||
}
|
||||
VisionManager.getCurrentUIVisionProcess().setDriverMode((Boolean) data.get("isDriver"));
|
||||
currentProcess.getDriverModeSettings().exposure = (Integer) data.get("exposure");
|
||||
currentProcess.getDriverModeSettings().brightness = (Integer) data.get("brightness");
|
||||
currentProcess.setDriverMode((Boolean) data.get("isDriver"));
|
||||
|
||||
// TODO: (HIGH) create saveCameras() function in VisionManager
|
||||
// VisionManager.saveCameras();
|
||||
VisionManager.saveCameras();
|
||||
break;
|
||||
}
|
||||
case "cameraSettings": {
|
||||
@@ -78,7 +76,7 @@ public class ServerHandler {
|
||||
currentCamera.getProperties().FOV = (double) newFOV;
|
||||
|
||||
if (currentProcess.cameraStreamer.getDivisor() != newStreamDivisor) {
|
||||
currentProcess.cameraStreamer.setDivisor(newStreamDivisor);
|
||||
currentProcess.cameraStreamer.setDivisor(newStreamDivisor, false);
|
||||
}
|
||||
|
||||
// TODO (HIGH) get and set video modes!
|
||||
@@ -87,8 +85,7 @@ public class ServerHandler {
|
||||
// currentCamera.getProperties().setCamVideoMode(newResolution, true);
|
||||
// }
|
||||
|
||||
// TODO: (HIGH) create saveCameras() function in VisionManager
|
||||
// VisionManager.saveCameras();
|
||||
VisionManager.saveCameras();
|
||||
sendFullSettings();
|
||||
break;
|
||||
}
|
||||
@@ -161,7 +158,7 @@ public class ServerHandler {
|
||||
break;
|
||||
}
|
||||
case "currentPipeline": {
|
||||
currentProcess.setPipeline((Integer) entry.getValue());
|
||||
currentProcess.setPipeline((Integer) entry.getValue(), true);
|
||||
sendFullSettings();
|
||||
try {
|
||||
currentCamera.setBrightness((int) currentPipeline.settings.brightness);
|
||||
@@ -194,16 +191,6 @@ public class ServerHandler {
|
||||
|
||||
private void setField(Object obj, String fieldName, Object value) {
|
||||
try {
|
||||
if (obj instanceof USBCamera) {
|
||||
// TODO: (HIGH) FIXXX!!!! this won't work anymore
|
||||
// the UI should instead understand that DriverMode is a pipeline (?)
|
||||
USBCamera cam = (USBCamera)obj;
|
||||
if (fieldName.equals("driverBrightness")) {
|
||||
cam.setDriverBrightness((Integer)value);
|
||||
} else if (fieldName.equals("driverExposure")) {
|
||||
cam.setDriverExposure((Integer)value);
|
||||
}
|
||||
}
|
||||
Field field = obj.getClass().getField(fieldName);
|
||||
if (field.getType().isEnum())
|
||||
field.set(obj, field.getType().getEnumConstants()[(Integer) value]);
|
||||
@@ -281,20 +268,24 @@ public class ServerHandler {
|
||||
public static void sendFullSettings() {
|
||||
//General settings
|
||||
Map<String, Object> fullSettings = new HashMap<>();
|
||||
|
||||
VisionProcess currentProcess = VisionManager.getCurrentUIVisionProcess();
|
||||
CameraProcess currentCamera = currentProcess.getCamera();
|
||||
CVPipeline currentPipeline = currentProcess.getCurrentPipeline();
|
||||
|
||||
try {
|
||||
fullSettings.put("settings", getOrdinalSettings());
|
||||
fullSettings.put("cameraSettings", getOrdinalCameraSettings());
|
||||
fullSettings.put("cameraList", VisionManager.getAllCameraNicknames());
|
||||
fullSettings.put("pipeline", getOrdinalPipeline());
|
||||
var currentVisionProcess = VisionManager.getCurrentUIVisionProcess();
|
||||
fullSettings.put("driverMode",getOrdinalDriver());
|
||||
fullSettings.put("driverMode", getOrdinalDriver());
|
||||
// TODO (HIGH) all of these settings!
|
||||
// fullSettings.put("pipelineList", currentVisionProcess.getPipelinesNickname());
|
||||
// fullSettings.put("resolutionList", currentVisionProcess.getResolutionList());
|
||||
// fullSettings.put("port", currentVisionProcess.getStreamPort());
|
||||
fullSettings.put("pipelineList", VisionManager.getCurrentCameraPipelineNicknames());
|
||||
fullSettings.put("resolutionList", VisionManager.getCurrentCameraResolutionList());
|
||||
fullSettings.put("port", currentProcess.cameraStreamer.getStreamPort());
|
||||
fullSettings.put("currentPipelineIndex", VisionManager.getCurrentUIVisionProcess().getCurrentPipelineIndex());
|
||||
// fullSettings.put("currentCameraIndex", VisionManager.getCurrentCameraIndex());
|
||||
} catch (CameraException | IllegalAccessException e) {
|
||||
fullSettings.put("currentCameraIndex", VisionManager.getCurrentUIVisionProcessIndex());
|
||||
} catch (IllegalAccessException e) {
|
||||
System.err.println("No camera found!");
|
||||
}
|
||||
broadcastMessage(fullSettings);
|
||||
|
||||
Reference in New Issue
Block a user