Full rewrite of camera system

This commit is contained in:
Banks Troutman
2019-09-19 14:07:42 -04:00
parent 760f62dd93
commit 508ccff766
16 changed files with 470 additions and 252 deletions

View File

@@ -1,9 +0,0 @@
package com.chameleonvision.vision;
public class CamVideoMode {
public int fps;
public int width;
public int height;
public String pixel_format;
}

View File

@@ -1,11 +0,0 @@
package com.chameleonvision.vision;
import java.util.HashMap;
public class Camera {
public Double FOV = 60.8;
public String path = "";
public HashMap<String, Pipeline> pipelines;
public int resolution = 0;
public CamVideoMode camVideoMode;
}

View File

@@ -8,7 +8,7 @@ public class GeneralSettings {
public String netmask = "";
public String hostname = "Chameleon-vision";
public String curr_camera = "";
public String curr_pipeline = "";
public Integer curr_pipeline = null;
}

View File

@@ -0,0 +1,25 @@
package com.chameleonvision.vision.camera;
import edu.wpi.cscore.VideoMode;
public class CamVideoMode {
public final int fps;
public final int width;
public final int height;
public final String pixel_format;
public CamVideoMode(VideoMode videoMode) {
fps = videoMode.fps;
width = videoMode.width;
height = videoMode.height;
pixel_format = videoMode.pixelFormat.name();
}
public VideoMode.PixelFormat getActualPixelFormat() {
return VideoMode.PixelFormat.valueOf(pixel_format);
}
public boolean isEqualToVideoMode(VideoMode videoMode) {
return videoMode.fps == fps && videoMode.width == width && videoMode.height == height && videoMode.pixelFormat == getActualPixelFormat();
}
}

View File

@@ -0,0 +1,132 @@
package com.chameleonvision.vision.camera;
import com.chameleonvision.vision.Pipeline;
import edu.wpi.cscore.UsbCamera;
import edu.wpi.cscore.UsbCameraInfo;
import edu.wpi.cscore.VideoMode;
import java.util.HashMap;
import java.util.stream.IntStream;
public class Camera {
private static double defaultFOV = 60.8;
public final String name;
public final String path;
public final UsbCamera UsbCam;
private final UsbCameraInfo UsbCamInfo;
private final VideoMode[] availableVideoModes;
private double FOV;
private CameraValues camVals;
private CamVideoMode camVideoMode;
private int currentPipelineIndex;
private HashMap<Integer, Pipeline> pipelines = new HashMap<>();
public Camera(String cameraName) {
this(cameraName, defaultFOV);
}
public Camera(UsbCameraInfo usbCamInfo) {
this(usbCamInfo, defaultFOV);
}
public Camera(String cameraName, double fov) {
this(CameraManager.AllUsbCameraInfosByName.get(cameraName), fov);
}
public Camera(UsbCameraInfo usbCamInfo, double fov) {
UsbCamInfo = usbCamInfo;
FOV = fov;
name = usbCamInfo.name;
path = usbCamInfo.path;
UsbCam = new UsbCamera(name, path);
// set up video mode
availableVideoModes = UsbCam.enumerateVideoModes();
setCamVideoMode(new CamVideoMode(availableVideoModes[0]));
}
public void setCamVideoMode(int videoMode) {
setCamVideoMode(UsbCam.enumerateVideoModes()[videoMode]);
}
private void setCamVideoMode(VideoMode videoMode) {
setCamVideoMode(new CamVideoMode(videoMode));
}
private void setCamVideoMode(CamVideoMode camVideoMode) {
this.camVideoMode = camVideoMode;
UsbCam.setPixelFormat(camVideoMode.getActualPixelFormat());
UsbCam.setFPS(camVideoMode.fps);
UsbCam.setResolution(camVideoMode.width, camVideoMode.height);
camVals = new CameraValues(this);
// TODO: Automatically restart CameraProcess when resolution changes (not FPS)
}
public void addPipeline() {
addPipeline(pipelines.size());
}
private void addPipeline(int pipelineNumber) {
if (pipelines.containsKey(pipelineNumber)) return;
pipelines.put(pipelineNumber, new Pipeline());
}
public void setCurrentPipelineIndex(int pipelineNumber) {
if (pipelineNumber - 1 > pipelines.size()) return;
currentPipelineIndex = pipelineNumber;
}
public Pipeline getCurrentPipeline() {
return pipelines.get(currentPipelineIndex);
}
public int getCurrentPipelineIndex() {
return currentPipelineIndex;
}
public HashMap<Integer, Pipeline> getPipelines() {
return pipelines;
}
public CamVideoMode getVideoMode() {
return camVideoMode;
}
public int getVideoModeIndex() {
return IntStream.range(0, availableVideoModes.length)
.filter(i -> camVideoMode.isEqualToVideoMode(availableVideoModes[i]))
.findFirst()
.orElse(-1);
}
public void setFOV(double fov) {
FOV = fov;
camVals = new CameraValues(this);
}
public double getFOV() {
return FOV;
}
public void setBrightness(int brightness) {
getCurrentPipeline().brightness = brightness;
UsbCam.setBrightness(brightness);
}
public int getBrightness() {
return getCurrentPipeline().brightness;
}
public void setExposure(int exposure) {
getCurrentPipeline().exposure = exposure;
UsbCam.setExposureManual(exposure);
}
}

View File

@@ -0,0 +1,133 @@
package com.chameleonvision.vision.camera;
import com.chameleonvision.FileHelper;
import com.chameleonvision.CameraException;
import com.chameleonvision.settings.SettingsManager;
import com.chameleonvision.vision.Pipeline;
import com.google.gson.Gson;
import com.google.gson.GsonBuilder;
import edu.wpi.cscore.UsbCamera;
import edu.wpi.cscore.UsbCameraInfo;
import org.opencv.videoio.VideoCapture;
import java.io.FileNotFoundException;
import java.io.FileReader;
import java.io.FileWriter;
import java.io.IOException;
import java.nio.file.Files;
import java.nio.file.Path;
import java.nio.file.Paths;
import java.util.ArrayList;
import java.util.HashMap;
import java.util.List;
public class CameraManager {
public static final Path CamConfigPath = Paths.get(SettingsManager.SettingsPath.toString(), "Cams");
// TODO: Fix suffix for camera
// TODO: throw a camera Exeption if no camera is connected
static HashMap<String, UsbCameraInfo> AllUsbCameraInfosByName = new HashMap<>() {{
var suffix = 0;
for (var info : UsbCamera.enumerateUsbCameras()) {
var cap = new VideoCapture(info.name);
if (cap.isOpened()) {
cap.release();
var name = String.format("%s(%s)", info.name, suffix);
put(name, info);
suffix++;
}
}
}};
private static HashMap<String, Camera> AllCamerasByName = new HashMap<>();
private static String currentCameraName;
public static HashMap<String, Camera> getAllCamerasByName() { return AllCamerasByName; }
public static void initializeCameras() {
FileHelper.CheckPath(CamConfigPath);
for (var entry : AllUsbCameraInfosByName.entrySet()) {
var camPath = Paths.get(CamConfigPath.toString(), String.format("%s.json", entry.getKey()));
if (Files.exists(camPath)) {
try {
// TODO: Check if deserializing correctly, if not, add CameraDeserializer
var camJsonFile = new FileReader(camPath.toString());
var gsonRead = new Gson().fromJson(camJsonFile, Camera.class);
AllCamerasByName.put(entry.getKey(), gsonRead);
} catch (FileNotFoundException ex) {
ex.printStackTrace();
}
} else {
if (!addCamera(new Camera(entry.getKey()))) {
System.err.println("Failed to add camera! Already exists!");
}
}
// TODO: Set currentCameraName from GeneralSettings instead of this
if (currentCameraName == null && AllCamerasByName.size() == 1) { // set current camera to first found
currentCameraName = AllCamerasByName.keySet().stream().findFirst().get();
}
}
}
private static boolean addCamera(Camera camera) {
if (AllCamerasByName.containsKey(camera.name)) return false;
camera.addPipeline();
AllCamerasByName.put(camera.name, camera);
return true;
}
public static Camera getCamera(String cameraName) {
return AllCamerasByName.get(cameraName);
}
public static void setCurrentCamera(String cameraName) throws CameraException {
if (!AllCamerasByName.containsKey(cameraName)) throw new CameraException(CameraException.CameraExceptionType.BAD_CAMERA);
currentCameraName = cameraName;
SettingsManager.getInstance().updateCameraSetting(cameraName, getCurrentCamera().getCurrentPipelineIndex());
}
public static Camera getCurrentCamera() throws CameraException {
if (AllCamerasByName.size() == 0) throw new CameraException(CameraException.CameraExceptionType.NO_CAMERA);
var curCam = AllCamerasByName.get(currentCameraName);
if (curCam == null) throw new CameraException(CameraException.CameraExceptionType.BAD_CAMERA);
return curCam;
}
public static void setCurrentPipeline(int pipelineNumber) throws CameraException {
if (!getCurrentCamera().getPipelines().containsKey(pipelineNumber)) throw new CameraException(CameraException.CameraExceptionType.BAD_PIPELINE);
getCurrentCamera().setCurrentPipelineIndex(pipelineNumber);
SettingsManager.getInstance().updatePipelineSetting(pipelineNumber);
}
public static Pipeline getCurrentPipeline() throws CameraException {
return getCurrentCamera().getCurrentPipeline();
}
public static List<String> getResolutionList() throws CameraException {
if (!currentCameraName.equals("")) {
List<String> list = new ArrayList<>();
var cam = CameraManager.getCamera(currentCameraName).UsbCam;
for (var res : cam.enumerateVideoModes()) {
list.add(String.format("%s X %s at %s fps", res.width, res.height, res.fps));
}
return list;
}
throw new CameraException(CameraException.CameraExceptionType.NO_CAMERA);
}
public static void saveCameras() {
for (var entry : AllCamerasByName.entrySet()) {
try {
Gson gson = new GsonBuilder().setPrettyPrinting().registerTypeAdapter(Camera.class, new CameraSerializer()).create();
FileWriter writer = new FileWriter(Paths.get(CamConfigPath.toString(), String.format("%s.json", entry.getKey())).toString());
gson.toJson(entry.getValue(), writer);
writer.flush();
writer.close();
} catch (IOException ex) {
ex.printStackTrace();
}
}
}
}

View File

@@ -0,0 +1,22 @@
package com.chameleonvision.vision.camera;
import com.google.gson.*;
import java.lang.reflect.Type;
public class CameraSerializer implements JsonSerializer<Camera> {
@Override
public JsonElement serialize(Camera camera, Type type, JsonSerializationContext context) {
JsonObject obj = new JsonObject();
obj.addProperty("FOV", camera.getFOV());
obj.addProperty("path", camera.path);
obj.addProperty("name", camera.name);
var pipelines = context.serialize(camera.getPipelines());
obj.add("pipelines", pipelines);
obj.addProperty("resolution", camera.getVideoModeIndex());
obj.add("camVideoMode", context.serialize(camera.getVideoMode()));
return obj;
}
}

View File

@@ -1,4 +1,4 @@
package com.chameleonvision.vision;
package com.chameleonvision.vision.camera;
import org.apache.commons.math3.fraction.Fraction;
import org.apache.commons.math3.util.FastMath;
@@ -20,7 +20,7 @@ public class CameraValues {
public final double VerticalFocalLength;
public CameraValues(Camera camera) {
this(camera.camVideoMode.width, camera.camVideoMode.height, camera.FOV);
this(camera.getVideoMode().width, camera.getVideoMode().height, camera.getFOV());
}
public CameraValues(int imageWidth, int imageHeight, double fov) {

View File

@@ -1,8 +1,11 @@
package com.chameleonvision.vision.process;
import com.chameleonvision.CameraException;
import com.chameleonvision.MemoryManager;
import com.chameleonvision.settings.SettingsManager;
import com.chameleonvision.vision.CameraValues;
import com.chameleonvision.vision.camera.Camera;
import com.chameleonvision.vision.camera.CameraManager;
import com.chameleonvision.vision.camera.CameraValues;
import com.chameleonvision.vision.Pipeline;
import com.chameleonvision.web.Server;
import edu.wpi.cscore.CvSink;
@@ -17,7 +20,9 @@ import java.util.HashMap;
import java.util.List;
public class CameraProcess implements Runnable {
private String CameraName;
private final Camera camera;
private final String cameraName;
// NetworkTables
private NetworkTableEntry ntPipelineEntry;
@@ -48,34 +53,38 @@ public class CameraProcess implements Runnable {
private Mat streamOutputMat = new Mat();
private Scalar contourRectColor = new Scalar(255, 0, 0);
private void ChangeCameraValues(int exposure, int brightness) {
SettingsManager.UsbCameras.get(CameraName).setBrightness(brightness);
SettingsManager.UsbCameras.get(CameraName).setExposureManual(exposure);
public void restartProcess() {
// TODO: Restart process and re-create cvPublish for new resolution
}
private void DriverModeListener(EntryNotification entryNotification) {
if (entryNotification.value.getBoolean()) {
ChangeCameraValues(25, 15);
camera.setExposure(25);
camera.setBrightness(15);
} else {
Pipeline pipeline = SettingsManager.Cameras.get(CameraName).pipelines.get(SettingsManager.CamerasCurrentPipeline.get(CameraName));
ChangeCameraValues(pipeline.exposure, pipeline.brightness);
Pipeline pipeline = camera.getCurrentPipeline();
camera.setExposure(pipeline.exposure);
camera.setBrightness(pipeline.brightness);
}
}
private void PipelineListener(EntryNotification entryNotification) {
if (SettingsManager.Cameras.get(CameraName).pipelines.containsKey(entryNotification.value.getString())) {
SettingsManager.CamerasCurrentPipeline.put(CameraName, entryNotification.value.getString());
Pipeline pipeline = SettingsManager.Cameras.get(CameraName).pipelines.get(SettingsManager.CamerasCurrentPipeline.get(CameraName));
ChangeCameraValues(pipeline.exposure, pipeline.brightness);
if (camera.getPipelines().containsKey(entryNotification.value.getString())) {
// camera.setPntryNotification.value.getString());
Pipeline pipeline = camera.getCurrentPipeline();
camera.setExposure(pipeline.exposure);
camera.setBrightness(pipeline.brightness);
//TODO Send Pipeline change using websocket to client
} else {
ntPipelineEntry.setString(SettingsManager.CamerasCurrentPipeline.get(CameraName));
ntPipelineEntry.setString("pipeline" + camera.getCurrentPipelineIndex());
}
}
public CameraProcess(String cameraName) {
CameraName = cameraName;
SettingsManager.CamerasCurrentPipeline.put(CameraName,SettingsManager.Cameras.get(CameraName).pipelines.keySet().stream().findFirst().toString());
public CameraProcess(Camera processCam) {
camera = processCam;
this.cameraName = camera.name;
// NetworkTables
NetworkTable ntTable = NetworkTableInstance.getDefault().getTable("/chameleon-vision/" + cameraName);
ntPipelineEntry = ntTable.getEntry("Pipeline");
@@ -88,17 +97,16 @@ public class CameraProcess implements Runnable {
ntDriverModeEntry.addListener(this::DriverModeListener, EntryListenerFlags.kUpdate);
ntPipelineEntry.addListener(this::PipelineListener, EntryListenerFlags.kUpdate);
ntDriverModeEntry.setBoolean(false);
ntPipelineEntry.setString(SettingsManager.CamerasCurrentPipeline.get(cameraName));
ntPipelineEntry.setString("pipeline" + camera.getCurrentPipelineIndex());
// camera settings
camVals = new CameraValues(SettingsManager.Cameras.get(cameraName));
camVals = new CameraValues(camera);
visionProcess = new VisionProcess(camVals);
// cscore setup
CameraServer cs = CameraServer.getInstance();
cvSink = cs.getVideo(SettingsManager.UsbCameras.get(cameraName));
cvSink = cs.getVideo(camera.UsbCam);
cvPublish = cs.putVideo(cameraName, camVals.ImageWidth, camVals.ImageHeight);
}
private void drawContour(Mat inputMat, RotatedRect contourRect) {
@@ -111,10 +119,18 @@ public class CameraProcess implements Runnable {
Imgproc.circle(inputMat, contourRect.center, 3, contourRectColor);
}
// TODO: Separate video output, contour drawing, data output to separate function, maybe even second thread
private void updateNetworkTables(PipelineResult pipelineResult) {
}
// TODO: Separate video output to separate function, maybe even second thread
private PipelineResult runVisionProcess(Mat inputImage, Mat outputImage) {
var pipelineResult = new PipelineResult();
if (currentPipeline == null) {
return pipelineResult;
}
Scalar hsvLower = new Scalar(currentPipeline.hue.get(0), currentPipeline.saturation.get(0), currentPipeline.value.get(0));
Scalar hsvUpper = new Scalar(currentPipeline.hue.get(1), currentPipeline.saturation.get(1), currentPipeline.value.get(1));
@@ -164,9 +180,9 @@ public class CameraProcess implements Runnable {
FoundContours.clear();
FilteredContours.clear();
GroupedContours.clear();
currentPipeline = SettingsManager.Cameras.get(CameraName).pipelines.get(SettingsManager.CamerasCurrentPipeline.get(CameraName));
// System.out.println(SettingsManager.CamerasCurrentPipeline.get(CameraName));
currentPipeline = camera.getCurrentPipeline();
// start fps counter right before grabbing input frame
startTime = System.nanoTime();
TimeStamp = cvSink.grabFrame(cameraInputMat);
@@ -183,10 +199,10 @@ public class CameraProcess implements Runnable {
ntPitchEntry.setNumber(pipelineResult.Pitch);
}
ntTimeStampEntry.setNumber(TimeStamp);
if (CameraName.equals(SettingsManager.GeneralSettings.curr_camera)){
if (cameraName.equals(SettingsManager.GeneralSettings.curr_camera) && pipelineResult.IsValid) {
HashMap<String,Object> WebSend = new HashMap<>();
HashMap<String,Object> point = new HashMap<>();
List<Double> center = new ArrayList<Double>();
List<Double> center = new ArrayList<>();
center.add(pipelineResult.RawPoint.center.x);
center.add(pipelineResult.RawPoint.center.y);
point.put("pitch", pipelineResult.Pitch);
@@ -200,7 +216,7 @@ public class CameraProcess implements Runnable {
// calculate FPS after publishing output frame
processTimeMs = (System.nanoTime() - startTime) * 1e-6;
fps = 1000 / processTimeMs;
System.out.printf("%s - Process time: %fms, FPS: %.2f, FoundContours: %d, FilteredContours: %d, GroupedContours: %d\n",CameraName ,processTimeMs, fps, FoundContours.size(), FilteredContours.size(), GroupedContours.size());
System.out.printf("%s - Process time: %fms, FPS: %.2f, FoundContours: %d, FilteredContours: %d, GroupedContours: %d\n", cameraName,processTimeMs, fps, FoundContours.size(), FilteredContours.size(), GroupedContours.size());
cameraInputMat.release();
hsvThreshMat.release();

View File

@@ -1,13 +1,12 @@
package com.chameleonvision.vision.process;
import com.chameleonvision.vision.CameraValues;
import com.chameleonvision.vision.camera.CameraValues;
import org.apache.commons.math3.util.FastMath;
import org.jetbrains.annotations.NotNull;
import org.opencv.core.*;
import org.opencv.imgproc.*;
import java.util.*;
import java.util.stream.Collectors;
public class VisionProcess {