finished integration between new client and backend

commands needs to be implemented
This commit is contained in:
ori agranat
2019-10-16 14:13:12 +03:00
parent 0828d2290a
commit dc2b738190
14 changed files with 75 additions and 45 deletions

View File

@@ -13,7 +13,8 @@ import java.util.stream.IntStream;
public class Camera {
private static final float DEFAULT_FOV = 60.8f;
private static final double DEFAULT_FOV = 60.8;
private static final StreamDivisor DEFAULT_STREAMDIVISOR = StreamDivisor.none;
private static final int MINIMUM_FPS = 30;
private static final int MINIMUM_WIDTH = 320;
private static final int MINIMUM_HEIGHT = 200;
@@ -29,8 +30,8 @@ public class Camera {
private final CvSink cvSink;
private final Object cvSourceLock = new Object();
private CvSource cvSource;
private float FOV;
private int streamDivisor;
private Double FOV;
private StreamDivisor streamDivisor;
private CameraValues camVals;
private CamVideoMode camVideoMode;
private int currentPipelineIndex;
@@ -40,27 +41,29 @@ public class Camera {
this(cameraName, DEFAULT_FOV);
}
public Camera(String cameraName, float fov) {
public Camera(String cameraName, double fov) {
this(cameraName,CameraManager.AllUsbCameraInfosByName.get(cameraName), fov);
}
public Camera(String cameraName, UsbCameraInfo usbCamInfo, float fov) {
this(cameraName ,usbCamInfo, fov, new HashMap<>(), 0);
public Camera(String cameraName, UsbCameraInfo usbCameraInfo, double fov) {
this(cameraName,usbCameraInfo, fov, DEFAULT_STREAMDIVISOR);
}
public Camera(String cameraName, UsbCameraInfo usbCamInfo, double fov,StreamDivisor divisor) {
this(cameraName ,usbCamInfo, fov, new HashMap<>(), 0, divisor);
}
public Camera(String cameraName, float fov, int videoModeIndex) {
this(cameraName, fov, new HashMap<>(), videoModeIndex);
public Camera(String cameraName, double fov, int videoModeIndex , StreamDivisor divisor) {
this(cameraName, fov, new HashMap<>(), videoModeIndex, divisor);
}
public Camera(String cameraName, float fov, HashMap<Integer, Pipeline> pipelines, int videoModeIndex) {
this(cameraName, CameraManager.AllUsbCameraInfosByName.get(cameraName), fov, pipelines, videoModeIndex);
public Camera(String cameraName, double fov, HashMap<Integer, Pipeline> pipelines, int videoModeIndex , StreamDivisor divisor) {
this(cameraName, CameraManager.AllUsbCameraInfosByName.get(cameraName), fov, pipelines, videoModeIndex, divisor);
}
public Camera(String cameraName, UsbCameraInfo usbCamInfo, float fov, HashMap<Integer, Pipeline> pipelines, int videoModeIndex) {
public Camera(String cameraName, UsbCameraInfo usbCamInfo, double fov, HashMap<Integer, Pipeline> pipelines, int videoModeIndex, StreamDivisor divisor) {
FOV = fov;
name = cameraName;
path = usbCamInfo.path;
streamDivisor = divisor;
UsbCam = new UsbCamera(name, path);
this.pipelines = pipelines;
@@ -143,11 +146,11 @@ public class Camera {
if (pipelineNumber - 1 > pipelines.size()) return;
currentPipelineIndex = pipelineNumber;
}
public int getStreamDivisor(){
public StreamDivisor getStreamDivisor(){
return streamDivisor;
}
public void setStreamDivisor(int divisor){
streamDivisor = divisor;
streamDivisor = StreamDivisor.values()[divisor];
}
public HashMap<Integer, Pipeline> getPipelines() {
@@ -165,12 +168,12 @@ public class Camera {
.orElse(-1);
}
public float getFOV() {
public double getFOV() {
return FOV;
}
public void setFOV(float fov) {
FOV = fov;
public void setFOV(Number fov) {
FOV = fov.doubleValue();
camVals = new CameraValues(this);
}

View File

@@ -14,9 +14,10 @@ public class CameraDeserializer implements JsonDeserializer<Camera> {
@Override
public Camera deserialize(JsonElement jsonElement, Type type, JsonDeserializationContext context) throws JsonParseException {
var jsonObj = jsonElement.getAsJsonObject();
var camFOV = jsonObj.get("FOV").getAsFloat();
var camFOV = jsonObj.get("FOV").getAsDouble();
var camName = jsonObj.get("name").getAsString();
var videoModeIndex = jsonObj.get("resolution").getAsInt();
var divisor = StreamDivisor.values()[jsonObj.get("streamDivisor").getAsInt()];
var pipelines = jsonObj.get("pipelines");
@@ -30,6 +31,6 @@ public class CameraDeserializer implements JsonDeserializer<Camera> {
e.printStackTrace();
}
return actualPipelines != null ? new Camera(camName, camFOV, actualPipelines, videoModeIndex) : new Camera(camName, camFOV, videoModeIndex);
return actualPipelines != null ? new Camera(camName, camFOV, actualPipelines, videoModeIndex,divisor) : new Camera(camName, camFOV, videoModeIndex, divisor);
}
}

View File

@@ -10,6 +10,7 @@ public class CameraSerializer implements JsonSerializer<Camera> {
obj.addProperty("FOV", camera.getFOV());
obj.addProperty("path", camera.path);
obj.addProperty("name", camera.name);
obj.addProperty("streamDivisor", camera.getStreamDivisor().ordinal());
var pipelines = context.serialize(camera.getPipelines());
obj.add("pipelines", pipelines);

View File

@@ -7,7 +7,7 @@ import org.apache.commons.math3.util.FastMath;
public class CameraValues {
public final int ImageWidth;
public final int ImageHeight;
public final float FOV;
public final double FOV;
public final double ImageArea;
public final double CenterX;
public final double CenterY;
@@ -24,7 +24,7 @@ public class CameraValues {
this(camera.getVideoMode().width, camera.getVideoMode().height, camera.getFOV());
}
public CameraValues(int imageWidth, int imageHeight, float fov) {
public CameraValues(int imageWidth, int imageHeight, double fov) {
ImageWidth = imageWidth;
ImageHeight = imageHeight;
FOV = fov;

View File

@@ -0,0 +1,14 @@
package com.chameleonvision.vision.camera;
public enum StreamDivisor {
none(1),
half(2),
quarter(4),
sixth(6);
public final Integer value;
StreamDivisor(int value) {
this.value = value;
}
}