diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java index 4da85e01d..ad30b001d 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java @@ -28,6 +28,8 @@ import java.util.function.Supplier; import org.opencv.core.Point; import org.photonvision.common.dataflow.CVPipelineResultConsumer; import org.photonvision.common.dataflow.structures.Packet; +import org.photonvision.common.logging.LogGroup; +import org.photonvision.common.logging.Logger; import org.photonvision.targeting.PhotonPipelineResult; import org.photonvision.targeting.PhotonTrackedTarget; import org.photonvision.targeting.TargetCorner; @@ -36,6 +38,7 @@ import org.photonvision.vision.target.TrackedTarget; public class NTDataPublisher implements CVPipelineResultConsumer { private final NetworkTable rootTable = NetworkTablesManager.getInstance().kRootTable; + private final Logger logger = new Logger(NTDataPublisher.class, LogGroup.Data); private NetworkTable subTable; private NetworkTableEntry rawBytesEntry; @@ -87,7 +90,7 @@ public class NTDataPublisher implements CVPipelineResultConsumer { } if (newIndex == originalIndex) { - // TODO: Log + logger.debug("Pipeline index is already " + newIndex); return; } @@ -95,9 +98,9 @@ public class NTDataPublisher implements CVPipelineResultConsumer { var setIndex = pipelineIndexSupplier.get(); if (newIndex != setIndex) { // set failed pipelineIndexEntry.forceSetNumber(setIndex); - // TODO: Log + logger.warn("Failed to set pipeline index to " + newIndex); } - // TODO: Log + logger.debug("Successfully set pipeline index to " + newIndex); } private void onDriverModeChange(EntryNotification entryNotification) { @@ -105,12 +108,12 @@ public class NTDataPublisher implements CVPipelineResultConsumer { var originalDriverMode = driverModeSupplier.getAsBoolean(); if (newDriverMode == originalDriverMode) { - // TODO: Log + logger.debug("Driver mode is already " + newDriverMode); return; } driverModeConsumer.accept(newDriverMode); - // TODO: Log + logger.debug("Successfully set driver mode to " + newDriverMode); } @SuppressWarnings("DuplicatedCode") diff --git a/photon-core/src/main/java/org/photonvision/common/scripting/ScriptManager.java b/photon-core/src/main/java/org/photonvision/common/scripting/ScriptManager.java index 7b8156e0a..bd54fb30f 100644 --- a/photon-core/src/main/java/org/photonvision/common/scripting/ScriptManager.java +++ b/photon-core/src/main/java/org/photonvision/common/scripting/ScriptManager.java @@ -128,7 +128,7 @@ public class ScriptManager { } public static void queueEvent(ScriptEventType eventType) { - if (!Platform.currentPlatform.isWindows()) { + if (!Platform.isWindows()) { try { queuedEvents.putLast(eventType); logger.info("Queued event: " + eventType.name()); diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java index 70af1499f..cdad1ca24 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameraSource.java @@ -44,7 +44,7 @@ public class USBCameraSource extends VisionSource { logger = new Logger(USBCameraSource.class, config.nickname, LogGroup.Camera); camera = new UsbCamera(config.nickname, config.path); - cvSink = CameraServer.getInstance().getVideo(this.camera); + cvSink = CameraServer.getVideo(this.camera); cameraQuirks = QuirkyCamera.getQuirkyCamera( diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java index 219cc3aa4..2774727d0 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/CVPipelineSettings.java @@ -107,4 +107,41 @@ public class CVPipelineSettings implements Cloneable { return null; } } + + @Override + public String toString() { + return "CVPipelineSettings{" + + "pipelineIndex=" + + pipelineIndex + + ", pipelineType=" + + pipelineType + + ", inputImageFlipMode=" + + inputImageFlipMode + + ", inputImageRotationMode=" + + inputImageRotationMode + + ", pipelineNickname='" + + pipelineNickname + + '\'' + + ", cameraExposure=" + + cameraExposure + + ", cameraBrightness=" + + cameraBrightness + + ", cameraGain=" + + cameraGain + + ", cameraRedGain=" + + cameraRedGain + + ", cameraBlueGain=" + + cameraBlueGain + + ", cameraVideoModeIndex=" + + cameraVideoModeIndex + + ", streamingFrameDivisor=" + + streamingFrameDivisor + + ", ledMode=" + + ledMode + + ", inputShouldShow=" + + inputShouldShow + + ", outputShouldShow=" + + outputShouldShow + + '}'; + } } diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java index 89142bd74..840b34e5a 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java @@ -92,6 +92,28 @@ public class PipelineManager { return null; } + /** + * Get the settings for a pipeline by index. + * + * @param index Index of pipeline whose nickname needs getting. + * @return the nickname of the pipeline whose index was provided. + */ + public String getPipelineNickname(int index) { + if (index < 0) { + switch (index) { + case DRIVERMODE_INDEX: + return driverModePipeline.getSettings().pipelineNickname; + case CAL_3D_INDEX: + return calibration3dPipeline.getSettings().pipelineNickname; + } + } + + for (var setting : userPipelineSettings) { + if (setting.pipelineIndex == index) return setting.pipelineNickname; + } + return null; + } + /** * Gets a list of nicknames for all user pipelines * diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java index 0ae694519..13148d281 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java @@ -370,6 +370,7 @@ public class VisionModule { void setPipeline(int index) { logger.info("Setting pipeline to " + index); + logger.info("Pipeline name: " + pipelineManager.getPipelineNickname(index)); pipelineManager.setIndex(index); var pipelineSettings = pipelineManager.getPipelineSettings(index); diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceSettables.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceSettables.java index 992c85db5..bbabf6ba9 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceSettables.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionSourceSettables.java @@ -62,6 +62,16 @@ public abstract class VisionSourceSettables { } public void setVideoMode(VideoMode mode) { + logger.info( + "Setting video mode to " + + "FPS: " + + mode.fps + + " Width: " + + mode.width + + " Height: " + + mode.height + + " Pixel Format: " + + mode.pixelFormat); setVideoModeInternal(mode); calculateFrameStaticProps(); } @@ -80,6 +90,7 @@ public abstract class VisionSourceSettables { } public void setFOV(double fov) { + logger.info("Setting FOV to " + fov); configuration.FOV = fov; calculateFrameStaticProps(); }