Files
PhotonVision/chameleon-server/src/main/java/com/chameleonvision/vision/VisionManager.java
oriagranat9 97a6e1419d V2.1 (#37)
* Toggle mode

* RangeSlider able to be disabled

* Added another window from the press of the button

* removed warning

* Major changes to colorpicker page

* Major changes to threshold tab

* fix for BGR not RGB

* Reverted changes of colorpicker.vue

* Updated Readme.md

Mainly Development Setup

* Update readme

small changes

* updated readme.md

Authors credit update

* updated readme.md 

added usb camera to hardware

* Updated UI readme

added nodejs installation and explanation

* Unit test vision (and implement networktable sending)

* finished color picker in the ui

* bugfix for correct tab

* cleanup and commenting

* Reveted changes to range slider

* bug fix for color picker

* Pipeline mat copy fix

* Added crosshair pipe

* compilation fix

* removed unsued comment

* moved calibration stuff to static class under 2d pipeline settings

* Added debug print commented

* Reverted subclass "Calibration"
Fixed bug where single point calibration causes crash when no target is found

* disable dual point crosshair for now

* Proper no target found fix, and snackbar error now showing

* Removed java fix for crash bug

* fixed problem with clear points in single point calibration

* change compatator to sqared values to make caluclation faster (no need for sqare root function)

* fixed roated camera too heigh for the UI

* Revert "fixed roated camera too heigh for the UI"

This reverts commit 50c8ecd345.

* fixed rotated camera too heigh for UI and corrected scalling

* updated pom to fix the camera buffer issue

* added pom variables

* Created new CaptureStaticProperties when rotating cam

* File stucture change, moved Pipeline implementation and their settings to /impl folder, refracted imports

* ignore auto created iml file

* ignore auto created iml file

* Fix lack of access problems after moving pipleline impl out of the same package

* Removed commented lines

* Fixed bug when selecting the same 90 deg rotation twice causes crosshair to move

* cleaned up single point calibration and bug fixed isBinary in driverMode

* Enum fix for the UI

* typo

* fixed Stream divisor problems see issue 19 in github issues

* fixed compilation error for test class

* Fixed problem when rotating camera with stream divisor

* Spelling + button style change

* Add speed limit to UI Updates

* Added runtime arg to fix settings permissions, and on-first-init

* Added FileHelper class to manage setting permissions for all files.

* Removed unnecessary argument

* NT can set pipeline to out on bound indexes

* bugfix in platform check

* added pipeline popup

* Round steam divisor resolution

* added regex test for camera name and pipe name

* Fix for Renaming pipeline leaves old config file #14

* Version change

* adde ( ) - and . to regex

* Replace NT timestamp with latency

* added back NT flush

* Add solvePNP, 3d tab on the UI, and some other misc bug fixes (#35)

* Rebase solvePNP on master

* added 3D tab minimap and csv reader

* More solvePNP

* Create draw pipe for pnp data

* SolvePNP piping work

* Move sorting into solvepnppipe

* Create calibration pipeline

* Update CalibrateSolvePNPPipeline.java

* add camera tilt angle

* Add calibration slider and snapshot button to 3D view

* Mirror updates in the socket handler

* add 3d calibration mode to the pipeline manager

* created calibration functions in ui and backend

* Start plumbing calibration

* Add snapshot and other handling to the RequestHandler

* added select resolution before starting calibration

* Rename solvePNPPipe to bounding box solve pnp pipe

* Update BoundingBoxSolvePNPPipe.java

* Add Mat serializer and CameraCalibrationConfig

* Begun calibration saving, fixed UI/Backend snapshot count mismatch

* Add (unplumbed) option to set checkerboard size

This will allow users to change the units their calibration is in

* Create chessboard.png

* Fix calibration NPE

* changed string serialization to a json send

* bug fixed cancellation button

* Fix spelling of snapshot in 3d.vue

* Plumb resolution change

* Set resolution during config, start on config serialization

* Update .gitignore

* Config fixes

* Start transition away from cvpipeline3d

* fix NPE on uncalibrated cameras

* clear list on fail

* Fix video mode index error

* ignore getters in camera calibration config

* Create json constructor for jsonmat

* get solvePNP mostly returning sane values

* Fix solvePNP bug and add unit test

* FIx calibration mat truncation

* added capture amount model upload and minimap data

* Standardize on meters in calibration and bounding box

* fix json out of bounds and handle null calibration more gracefully

* don't put text on calibrate image, go back to inches

* convert distance to meters

this means calibration will need to be in inches

* Actually save raw contor

* Update GroupContoursPipe.java

* Add all calibration return to camera capture

* hard code 2019 target

* bugfixed draw2d added fail calib popup, merge end and cancel

added the res index to the calib start

* Clarify error message and draw more fancy rectangles

* Cleanup memory in solvepnp

* re did minimap component

* fix npe if left/right is null

* remove references to 2d

* try-catch running the current pipeline

* Add method to find corners using the harris corner detector

* Possibly fix left/right missmatch

* Fix 3D Tab error

* FIx file permissions, mat serializer adjustments

* fixed mini map for field coordinates

* mini map changes fov

* Update SolvePNPPipe.java

* get rid of target corners

* some memory leak fixes

* fixed mini map location

* added position under minimap

* changed player fov look

* put all targets in the web send

* re did target send to ui added target tables, bugfix calibration

* fixed y position

* Add tilt angle to capture properties

* maybe fix y axis in minimap

* Add square size to onCalibrationEnding

* Possibly add square size to UI

* fix NPE with pitch

* Fix bug with sending multiple targets

* Only instantiate 3d stuff if we are in 3d mode

* Fix array list exceptions

* Fix bug in sort contors

list was truncated too early

* added download chess, tilt setting and ordinal tilt,

* added square size connection

* removed unused code

* Update pom version to 2.1-RELEASE

* Send camera calibrations to UI

* Stream pose list to a LIst

* Only stream necessary parts of the aux list entry

* Make broadcastMessage synchronized to prevent ConcurrentModificationExceptions

* added fps counter changed squaresize steps bug fixes in tables

* bugfix camera settings cam wont change

Authored-by: oriagranat9 <oriagranat9@gmail.com>

* disable pose print

* standardize on calibration in inches and add square size as a divisor

This should do the same thing as calibrating in the correct units but it doesnt like meeeeee

* updated pom for release, 3d calibration change, cosmetic changes

* WIP: 3D res filter

* bug fix in index parsing

* add good features to track point finder

* offset found corners by old tl position

* Add method to find most extreme per-quadrant points for solvePNP

* re did pipeline duplication

* Add release method to standard cv pipeline

* remove contor from tracked target

* Explicitly release all the intermediate results

* avoid creating new mats in group contors pipe

* removed mat release

* updated pom

* Actually cache the last target

We were trying to but i never hooked this part up

* Fix memory leak in sort contros pipe

* Fix memory leak in sort contors pipe

* Help more with memory usage in speckle reject and draw pipes

* minor bugfixes to the ui

* Start moving stream into vision process

Should probs move into a pipe to be idimatic

* justify bug fix

* Fix sort left/right bug

* Fix target grouping bug

* Avoid allocating a new mat in solvePNP, perf. increases in group contors pipe

* Event scripts (#36)

* Begin scripting work

* More scripting work

* Finalize scripting system

* Begin implementing script events

* Finalize script system

Co-authored-by: Banks T <btrout.dhrs@gmail.com>

Co-authored-by: OmerZ7 <zipory.omer@gmail.com>
Co-authored-by: Matt <matthew.morley.ca@gmail.com>
Co-authored-by: Banks T <btrout.dhrs@gmail.com>
2020-01-04 11:53:18 -08:00

184 lines
7.2 KiB
Java

package com.chameleonvision.vision;
import com.chameleonvision.config.CameraConfig;
import com.chameleonvision.config.CameraJsonConfig;
import com.chameleonvision.config.ConfigManager;
import com.chameleonvision.config.FullCameraConfiguration;
import com.chameleonvision.util.Helpers;
import com.chameleonvision.util.Platform;
import com.chameleonvision.vision.camera.USBCameraCapture;
import com.chameleonvision.vision.pipeline.CVPipelineSettings;
import edu.wpi.cscore.UsbCamera;
import edu.wpi.cscore.UsbCameraInfo;
import org.opencv.videoio.VideoCapture;
import java.util.*;
import java.util.stream.Collectors;
public class VisionManager {
private VisionManager() {
}
private static final LinkedHashMap<String, UsbCameraInfo> usbCameraInfosByCameraName = new LinkedHashMap<>();
private static final LinkedList<FullCameraConfiguration> loadedCameraConfigs = new LinkedList<>();
private static final LinkedList<VisionProcessManageable> visionProcesses = new LinkedList<>();
@SuppressWarnings("WeakerAccess")
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;
public static boolean initializeSources() {
int suffix = 0;
for (UsbCameraInfo info : UsbCamera.enumerateUsbCameras()) {
VideoCapture cap = new VideoCapture(info.dev);
if (cap.isOpened()) {
cap.release();
String name = info.name;
while (usbCameraInfosByCameraName.containsKey(name)) {
suffix++;
name = String.format("%s (%d)", name, suffix);
}
usbCameraInfosByCameraName.put(name, info);
}
}
if (usbCameraInfosByCameraName.isEmpty()) {
return false;
}
// load the config
List<CameraJsonConfig> preliminaryConfigs = new ArrayList<>();
usbCameraInfosByCameraName.forEach((suffixedName, cameraInfo) -> {
String truePath;
if (Platform.CurrentPlatform.isWindows()) {
truePath = cameraInfo.path;
} else {
truePath = Arrays.stream(cameraInfo.otherPaths).filter(x -> x.contains("/dev/v4l/by-path")).findFirst().orElse(cameraInfo.path);
}
preliminaryConfigs.add(new CameraJsonConfig(truePath, suffixedName));
});
loadedCameraConfigs.addAll(ConfigManager.initializeCameras(preliminaryConfigs));
return true;
}
public static boolean initializeProcesses() {
for (int i = 0; i < loadedCameraConfigs.size(); i++) {
FullCameraConfiguration config = loadedCameraConfigs.get(i);
CameraJsonConfig cameraJsonConfig = config.cameraConfig;
USBCameraCapture camera = new USBCameraCapture(config);
VisionProcess process = new VisionProcess(camera, config);
process.pipelineManager.driverModePipeline.settings = config.driverMode;
visionProcesses.add(new VisionProcessManageable(i, cameraJsonConfig.name, process));
}
currentUIVisionProcess = getVisionProcessByIndex(0);
ConfigManager.settings.currentCamera = visionProcesses.get(0).name;
return true;
}
public static void startProcesses() {
visionProcesses.forEach((vpm) -> vpm.visionProcess.start());
}
public static VisionProcess getCurrentUIVisionProcess() {
return currentUIVisionProcess;
}
public static CameraConfig getCurrentCameraConfig() {
return getCameraConfig(currentUIVisionProcess);
}
public static CameraConfig getCameraConfig(VisionProcess process) {
String cameraName = process.getCamera().getProperties().name;
return Objects.requireNonNull(loadedCameraConfigs.stream().filter(x -> x.cameraConfig.name.equals(cameraName)).findFirst().orElse(null)).fileConfig;
}
public static void setCurrentProcessByIndex(int processIndex) {
if (processIndex > visionProcesses.size() - 1) {
return;
}
currentUIVisionProcess = getVisionProcessByIndex(processIndex);
ConfigManager.settings.currentCamera = visionProcesses.get(processIndex).name;
}
public static VisionProcess getVisionProcessByIndex(int processIndex) {
if (processIndex > visionProcesses.size() - 1) {
return null;
}
VisionProcessManageable vpm = visionProcesses.stream().filter(manageable -> manageable.index == processIndex).findFirst().orElse(null);
return vpm != null ? vpm.visionProcess : null;
}
public static List<String> getAllCameraNicknames() {
return visionProcesses.stream().map(vpm -> vpm.visionProcess.getCamera()
.getProperties().getNickname()).collect(Collectors.toList());
}
public static List<String> getCurrentCameraPipelineNicknames() {
return currentUIVisionProcess.pipelineManager.pipelines.stream().map(cvPipeline -> cvPipeline.settings.nickname).collect(Collectors.toList());
}
public static void saveAllCameras() {
visionProcesses.forEach((vpm) -> {
VisionProcess process = vpm.visionProcess;
String cameraName = process.getCamera().getProperties().name;
List<CVPipelineSettings> pipelines = process.pipelineManager.pipelines.stream().map(cvPipeline -> cvPipeline.settings).collect(Collectors.toList());
CVPipelineSettings driverMode = process.getDriverModeSettings();
CameraJsonConfig config = CameraJsonConfig.fromVisionProcess(process);
ConfigManager.saveCameraPipelines(cameraName, pipelines);
ConfigManager.saveCameraDriverMode(cameraName, driverMode);
ConfigManager.saveCameraConfig(cameraName, config);
});
}
private static String getCurrentCameraName() {
return currentUIVisionProcess.getCamera().getProperties().name;
}
public static void saveCurrentCameraSettings() {
CameraJsonConfig config = CameraJsonConfig.fromVisionProcess(currentUIVisionProcess);
ConfigManager.saveCameraConfig(getCurrentCameraName(), config);
}
public static void saveCurrentCameraPipelines() {
currentUIVisionProcess.pipelineManager.saveAllPipelines();
}
public static void saveCurrentCameraDriverMode() {
currentUIVisionProcess.pipelineManager.saveDriverModeConfig();
}
private static List<HashMap> getCameraResolutionList(USBCameraCapture capture) {
return capture.getProperties().getVideoModes().stream().map(Helpers::VideoModeToHashMap).collect(Collectors.toList());
}
public static List<HashMap> getCurrentCameraResolutionList() {
return getCameraResolutionList(currentUIVisionProcess.getCamera());
}
public static int getCurrentUIVisionProcessIndex() {
VisionProcessManageable vpm = visionProcesses.stream().filter(v -> v.visionProcess == currentUIVisionProcess).findFirst().orElse(null);
return vpm != null ? vpm.index : -1;
}
}