Convert to user selected camera matching (#1556)

This commit is contained in:
oh-yes-0-fps
2025-01-01 03:04:20 -05:00
committed by GitHub
parent b2e70a7257
commit 418eada0b5
67 changed files with 2710 additions and 1948 deletions

View File

@@ -19,12 +19,9 @@ package org.photonvision;
import edu.wpi.first.hal.HAL;
import java.io.IOException;
import java.nio.file.Files;
import java.nio.file.Path;
import java.util.ArrayList;
import java.util.List;
import java.util.Objects;
import java.util.stream.Collectors;
import org.apache.commons.cli.*;
import org.photonvision.common.configuration.CameraConfiguration;
import org.photonvision.common.configuration.ConfigManager;
@@ -41,25 +38,17 @@ import org.photonvision.common.logging.Logger;
import org.photonvision.common.logging.PvCSCoreLogger;
import org.photonvision.common.networking.NetworkManager;
import org.photonvision.common.util.TestUtils;
import org.photonvision.common.util.numbers.IntegerCouple;
import org.photonvision.jni.PhotonTargetingJniLoader;
import org.photonvision.jni.RknnDetectorJNI;
import org.photonvision.mrcal.MrCalJNILoader;
import org.photonvision.raspi.LibCameraJNILoader;
import org.photonvision.server.Server;
import org.photonvision.vision.apriltag.AprilTagFamily;
import org.photonvision.vision.camera.FileVisionSource;
import org.photonvision.vision.camera.PVCameraInfo;
import org.photonvision.vision.opencv.CVMat;
import org.photonvision.vision.opencv.ContourGroupingMode;
import org.photonvision.vision.opencv.ContourShape;
import org.photonvision.vision.pipeline.AprilTagPipelineSettings;
import org.photonvision.vision.pipeline.CVPipelineSettings;
import org.photonvision.vision.pipeline.ColoredShapePipelineSettings;
import org.photonvision.vision.pipeline.PipelineProfiler;
import org.photonvision.vision.pipeline.ReflectivePipelineSettings;
import org.photonvision.vision.processes.VisionModule;
import org.photonvision.vision.processes.VisionModuleManager;
import org.photonvision.vision.processes.VisionSource;
import org.photonvision.vision.processes.VisionSourceManager;
import org.photonvision.vision.target.TargetModel;
@@ -126,11 +115,6 @@ public class Main {
}
}
if (cmd.hasOption("ignore-cameras")) {
VisionSourceManager.getInstance()
.setIgnoredCamerasRegex(cmd.getOptionValue("ignore-cameras"));
}
if (cmd.hasOption("disable-networking")) {
NetworkManager.getInstance().networkingIsDisabled = true;
}
@@ -146,156 +130,27 @@ public class Main {
return true;
}
private static void addTestModeFromFolder() {
ConfigManager.getInstance().load();
try {
List<VisionSource> collectedSources =
Files.list(testModeFolder)
.filter(p -> p.toFile().isFile())
.map(
p -> {
try {
CameraConfiguration camConf =
new CameraConfiguration(
p.getFileName().toString(), p.toAbsolutePath().toString());
camConf.FOV = TestUtils.WPI2019Image.FOV; // Good guess?
camConf.addCalibration(TestUtils.get2020LifeCamCoeffs(false));
var pipeSettings = new AprilTagPipelineSettings();
pipeSettings.pipelineNickname = p.getFileName().toString();
pipeSettings.outputShowMultipleTargets = true;
pipeSettings.inputShouldShow = true;
pipeSettings.outputShouldShow = false;
pipeSettings.solvePNPEnabled = true;
var aprilTag = new AprilTagPipelineSettings();
var psList = new ArrayList<CVPipelineSettings>();
psList.add(aprilTag);
camConf.pipelineSettings = psList;
return new FileVisionSource(camConf);
} catch (Exception e) {
logger.error("Couldn't load image " + p.getFileName().toString(), e);
return null;
}
})
.filter(Objects::nonNull)
.collect(Collectors.toList());
ConfigManager.getInstance().unloadCameraConfigs();
VisionModuleManager.getInstance().addSources(collectedSources).forEach(VisionModule::start);
ConfigManager.getInstance().addCameraConfigurations(collectedSources);
} catch (IOException e) {
logger.error("Path does not exist!");
System.exit(1);
}
}
private static void addTestModeSources() {
ConfigManager.getInstance().load();
var camConf2019 =
ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2019");
if (camConf2019 == null) {
camConf2019 =
new CameraConfiguration("WPI2019", TestUtils.getTestMode2019ImagePath().toString());
camConf2019.FOV = TestUtils.WPI2019Image.FOV;
camConf2019.calibrations.add(TestUtils.get2019LifeCamCoeffs(true));
var pipeline2019 = new ReflectivePipelineSettings();
pipeline2019.pipelineNickname = "CargoShip";
pipeline2019.targetModel = TargetModel.k2019DualTarget;
pipeline2019.outputShowMultipleTargets = true;
pipeline2019.contourGroupingMode = ContourGroupingMode.Dual;
pipeline2019.inputShouldShow = true;
var psList2019 = new ArrayList<CVPipelineSettings>();
psList2019.add(pipeline2019);
camConf2019.pipelineSettings = psList2019;
}
var camConf2020 =
ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2020");
if (camConf2020 == null) {
camConf2020 =
new CameraConfiguration("WPI2020", TestUtils.getTestMode2020ImagePath().toString());
camConf2020.FOV = TestUtils.WPI2020Image.FOV;
camConf2020.calibrations.add(TestUtils.get2019LifeCamCoeffs(true));
var pipeline2020 = new ReflectivePipelineSettings();
pipeline2020.pipelineNickname = "OuterPort";
pipeline2020.targetModel = TargetModel.k2020HighGoalOuter;
camConf2020.calibrations.add(TestUtils.get2020LifeCamCoeffs(true));
pipeline2020.inputShouldShow = true;
var psList2020 = new ArrayList<CVPipelineSettings>();
psList2020.add(pipeline2020);
camConf2020.pipelineSettings = psList2020;
}
var camConf2022 =
ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2022");
if (camConf2022 == null) {
camConf2022 =
new CameraConfiguration("WPI2022", TestUtils.getTestMode2022ImagePath().toString());
camConf2022.FOV = TestUtils.WPI2022Image.FOV;
camConf2022.calibrations.add(TestUtils.get2019LifeCamCoeffs(true));
var pipeline2022 = new ReflectivePipelineSettings();
pipeline2022.pipelineNickname = "OuterPort";
pipeline2022.targetModel = TargetModel.k2020HighGoalOuter;
pipeline2022.inputShouldShow = true;
// camConf2020.calibrations.add(TestUtils.get2020LifeCamCoeffs(true));
var psList2022 = new ArrayList<CVPipelineSettings>();
psList2022.add(pipeline2022);
camConf2022.pipelineSettings = psList2022;
}
CameraConfiguration camConf2023 =
ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2023");
if (camConf2023 == null) {
camConf2023 =
new CameraConfiguration(
"WPI2023",
TestUtils.getResourcesFolderPath(true)
.resolve("testimages")
.resolve(TestUtils.WPI2023Apriltags.k383_60_Angle2.path)
.toString());
camConf2023.FOV = TestUtils.WPI2023Apriltags.FOV;
camConf2023.calibrations.add(TestUtils.get2023LifeCamCoeffs(true));
var pipeline2023 = new AprilTagPipelineSettings();
var path_split = Path.of(camConf2023.path).getFileName().toString();
pipeline2023.pipelineNickname = path_split.replace(".png", "");
pipeline2023.targetModel = TargetModel.kAprilTag6in_16h5;
pipeline2023.inputShouldShow = true;
pipeline2023.solvePNPEnabled = true;
var psList2023 = new ArrayList<CVPipelineSettings>();
psList2023.add(pipeline2023);
camConf2023.pipelineSettings = psList2023;
}
CameraConfiguration camConf2024 =
ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2024");
if (camConf2024 == null) {
if (camConf2024 == null || true) {
camConf2024 =
new CameraConfiguration(
"WPI2024",
TestUtils.getResourcesFolderPath(true)
.resolve("testimages")
.resolve(TestUtils.WPI2024Images.kSpeakerCenter_143in.path)
.toString());
PVCameraInfo.fromFileInfo(
TestUtils.getResourcesFolderPath(true)
.resolve("testimages")
.resolve(TestUtils.WPI2024Images.kSpeakerCenter_143in.path)
.toString(),
"WPI2024"));
camConf2024.FOV = TestUtils.WPI2024Images.FOV;
// same camera as 2023
camConf2024.calibrations.add(TestUtils.get2023LifeCamCoeffs(true));
var pipeline2024 = new AprilTagPipelineSettings();
var path_split = Path.of(camConf2024.path).getFileName().toString();
var path_split = Path.of(camConf2024.matchedCameraInfo.path()).getFileName().toString();
pipeline2024.pipelineNickname = path_split.replace(".jpg", "");
pipeline2024.targetModel = TargetModel.kAprilTag6p5in_36h11;
pipeline2024.tagFamily = AprilTagFamily.kTag36h11;
@@ -307,47 +162,11 @@ public class Main {
camConf2024.pipelineSettings = psList2024;
}
// Colored shape testing
var camConfShape =
ConfigManager.getInstance().getConfig().getCameraConfigurations().get("Shape");
// If we haven't saved shape settings, create a new one
if (camConfShape == null) {
camConfShape =
new CameraConfiguration(
"Shape",
TestUtils.getPowercellImagePath(TestUtils.PowercellTestImages.kPowercell_test_1, true)
.toString());
var settings = new ColoredShapePipelineSettings();
settings.hsvHue = new IntegerCouple(0, 35);
settings.hsvSaturation = new IntegerCouple(82, 255);
settings.hsvValue = new IntegerCouple(62, 255);
settings.contourShape = ContourShape.Triangle;
settings.outputShowMultipleTargets = true;
settings.circleAccuracy = 15;
settings.inputShouldShow = true;
camConfShape.addPipelineSetting(settings);
}
var collectedSources = new ArrayList<VisionSource>();
var fvsShape = new FileVisionSource(camConfShape);
var fvs2019 = new FileVisionSource(camConf2019);
var fvs2020 = new FileVisionSource(camConf2020);
var fvs2022 = new FileVisionSource(camConf2022);
var fvs2023 = new FileVisionSource(camConf2023);
var fvs2024 = new FileVisionSource(camConf2024);
collectedSources.add(fvs2024);
// collectedSources.add(fvs2023);
// collectedSources.add(fvs2022);
// collectedSources.add(fvsShape);
// collectedSources.add(fvs2020);
// collectedSources.add(fvs2019);
var cameraConfigs = List.of(camConf2024);
ConfigManager.getInstance().unloadCameraConfigs();
VisionModuleManager.getInstance().addSources(collectedSources).forEach(VisionModule::start);
ConfigManager.getInstance().addCameraConfigurations(collectedSources);
cameraConfigs.stream().forEach(ConfigManager.getInstance()::addCameraConfiguration);
VisionSourceManager.getInstance().registerLoadedConfigs(cameraConfigs);
}
public static void main(String[] args) {
@@ -475,21 +294,21 @@ public class Main {
System.exit(0);
}
// todo - should test mode just add test mode sources, but still allow local usb cameras to be
// added?
if (!isTestMode) {
logger.debug("Loading VisionSourceManager...");
VisionSourceManager.getInstance()
.registerLoadedConfigs(
ConfigManager.getInstance().getConfig().getCameraConfigurations().values());
VisionSourceManager.getInstance().registerTimedTask();
} else {
if (testModeFolder == null) {
addTestModeSources();
} else {
addTestModeFromFolder();
}
}
VisionSourceManager.getInstance().registerTimedTasks();
logger.info("Starting server...");
HardwareManager.getInstance().setRunning(true);
Server.initialize(DEFAULT_WEBPORT);

View File

@@ -52,7 +52,8 @@ import org.photonvision.common.util.file.JacksonUtils;
import org.photonvision.common.util.file.ProgramDirectoryUtilities;
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
import org.photonvision.vision.camera.CameraQuirk;
import org.photonvision.vision.processes.VisionModuleManager;
import org.photonvision.vision.camera.PVCameraInfo;
import org.photonvision.vision.processes.VisionSourceManager;
import org.zeroturnaround.zip.ZipUtil;
public class RequestHandler {
@@ -395,7 +396,7 @@ public class RequestHandler {
logger.info("Changing camera FOV to: " + fov);
logger.info("Changing quirks to: " + settings.quirksToChange.toString());
var module = VisionModuleManager.getInstance().getModule(index);
var module = VisionSourceManager.getInstance().vmm.getModule(index);
module.setFov(fov);
module.changeCameraQuirks(settings.quirksToChange);
@@ -474,7 +475,7 @@ public class RequestHandler {
try {
index = kObjectMapper.readTree(ctx.bodyInputStream()).get("index").asInt();
var calData = VisionModuleManager.getInstance().getModule(index).endCalibration();
var calData = VisionSourceManager.getInstance().vmm.getModule(index).endCalibration();
if (calData == null) {
ctx.result("The calibration process failed");
ctx.status(500);
@@ -551,7 +552,7 @@ public class RequestHandler {
String name = data.get("name").asText();
int idx = data.get("cameraIndex").asInt();
VisionModuleManager.getInstance().getModule(idx).setCameraNickname(name);
VisionSourceManager.getInstance().vmm.getModule(idx).setCameraNickname(name);
ctx.status(200);
ctx.result("Successfully changed the camera name to: " + name);
logger.info("Successfully changed the camera name to: " + name);
@@ -581,7 +582,8 @@ public class RequestHandler {
var observationIdx = Integer.parseInt(ctx.queryParam("snapshotIdx"));
CameraCalibrationCoefficients calList =
VisionModuleManager.getInstance()
VisionSourceManager.getInstance()
.vmm
.getModule(idx)
.getStateAsCameraConfig()
.calibrations
@@ -631,7 +633,7 @@ public class RequestHandler {
var width = Integer.parseInt(ctx.queryParam("width"));
var height = Integer.parseInt(ctx.queryParam("height"));
var cc = VisionModuleManager.getInstance().getModule(idx).getStateAsCameraConfig();
var cc = VisionSourceManager.getInstance().vmm.getModule(idx).getStateAsCameraConfig();
CameraCalibrationCoefficients calList =
cc.calibrations.stream()
@@ -818,19 +820,63 @@ public class RequestHandler {
FileUtils.deleteDirectory(cameraDir);
}
// prevent -anyone- else from writing camera configs -- but flush first
ConfigManager.getInstance().saveToDisk();
ConfigManager.getInstance().setWriteTaskEnabled(false);
ConfigManager.getInstance().disableFlushOnShutdown();
// remove the config from the global config and force-flush
ConfigManager.getInstance().getConfig().removeCameraConfig(name);
ConfigManager.getInstance().saveToDisk();
VisionSourceManager.getInstance().deleteVisionSource(name);
ctx.status(200);
restartProgram();
} catch (IOException e) {
// todo
logger.error("asdf", e);
ctx.status(500);
}
}
public static void onActivateMatchedCameraRequest(Context ctx) {
logger.info(ctx.queryString().toString());
String uniqueName = ctx.queryParam("uniqueName");
if (VisionSourceManager.getInstance().reactivateDisabledCameraConfig(uniqueName)) {
ctx.status(200);
} else {
ctx.status(403);
}
ctx.result("Successfully assigned camera with unique name: " + uniqueName);
}
public static void onAssignUnmatchedCameraRequest(Context ctx) {
logger.info(ctx.queryString().toString());
PVCameraInfo camera;
try {
camera = JacksonUtils.deserialize(ctx.queryParam("cameraInfo"), PVCameraInfo.class);
} catch (IOException e) {
ctx.status(401);
return;
}
if (VisionSourceManager.getInstance().assignUnmatchedCamera(camera)) {
ctx.status(200);
} else {
ctx.status(403);
}
ctx.result("Successfully assigned camera: " + camera);
}
public static void onUnassignCameraRequest(Context ctx) {
logger.info(ctx.queryString().toString());
String uniqueName = ctx.queryParam("uniqueName");
if (VisionSourceManager.getInstance().deactivateVisionSource(uniqueName)) {
ctx.status(200);
} else {
ctx.status(403);
}
ctx.status(200);
ctx.result("Successfully assigned camera with unique name: " + uniqueName);
}
}

View File

@@ -136,6 +136,9 @@ public class Server {
app.get("/api/utils/getCalibrationJSON", RequestHandler::onCalibrationExportRequest);
app.post("/api/utils/nukeConfigDirectory", RequestHandler::onNukeConfigDirectory);
app.post("/api/utils/nukeOneCamera", RequestHandler::onNukeOneCamera);
app.post("/api/utils/activateMatchedCamera", RequestHandler::onActivateMatchedCameraRequest);
app.post("/api/utils/assignUnmatchedCamera", RequestHandler::onAssignUnmatchedCameraRequest);
app.post("/api/utils/unassignCamera", RequestHandler::onUnassignCameraRequest);
// Calibration
app.post("/api/calibration/end", RequestHandler::onCalibrationEndRequest);