From 953b6cd9590f7e2f6f28ec26f6697535c9743495 Mon Sep 17 00:00:00 2001 From: Titan Robotics Club Date: Wed, 13 Sep 2023 13:18:02 -0700 Subject: [PATCH] Updated FtcLib. Removed setXXXXAnnotateEnabled methods. It should be a parameter in the construction of color blob vision just like other vision processors. --- TeamCode/src/main/java/TrcFtcLib | 2 +- TeamCode/src/main/java/teamcode/FtcAuto.java | 2 - TeamCode/src/main/java/teamcode/FtcTest.java | 2 - .../src/main/java/teamcode/vision/Vision.java | 46 ++----------------- 4 files changed, 6 insertions(+), 46 deletions(-) diff --git a/TeamCode/src/main/java/TrcFtcLib b/TeamCode/src/main/java/TrcFtcLib index eeb481545727..42374bd3acec 160000 --- a/TeamCode/src/main/java/TrcFtcLib +++ b/TeamCode/src/main/java/TrcFtcLib @@ -1 +1 @@ -Subproject commit eeb4815457271c7ec6a3d768c1774fa07b924be9 +Subproject commit 42374bd3aceca52fd2aeef15e28a4c6f60d1e230 diff --git a/TeamCode/src/main/java/teamcode/FtcAuto.java b/TeamCode/src/main/java/teamcode/FtcAuto.java index 6e4243bede2f..8d2c1b7248bd 100644 --- a/TeamCode/src/main/java/teamcode/FtcAuto.java +++ b/TeamCode/src/main/java/teamcode/FtcAuto.java @@ -173,14 +173,12 @@ public void robotInit() { robot.globalTracer.traceInfo(funcName, "Enabling RedBlobVision."); robot.vision.setRedBlobVisionEnabled(true); - robot.vision.setRedBlobAnnotateEnabled(true); } if (robot.vision.blueBlobVision != null) { robot.globalTracer.traceInfo(funcName, "Enabling BlueBlobVision."); robot.vision.setBlueBlobVisionEnabled(true); - robot.vision.setBlueBlobAnnotateEnabled(true); } if (robot.vision.tensorFlowVision != null) diff --git a/TeamCode/src/main/java/teamcode/FtcTest.java b/TeamCode/src/main/java/teamcode/FtcTest.java index 3bc8f5bf4676..4e899abea8c3 100644 --- a/TeamCode/src/main/java/teamcode/FtcTest.java +++ b/TeamCode/src/main/java/teamcode/FtcTest.java @@ -273,14 +273,12 @@ public void startMode(TrcRobot.RunMode prevMode, TrcRobot.RunMode nextMode) { robot.globalTracer.traceInfo(funcName, "Enabling RedBlobVision."); robot.vision.setRedBlobVisionEnabled(true); - robot.vision.setRedBlobAnnotateEnabled(true); } if (robot.vision.blueBlobVision != null) { robot.globalTracer.traceInfo(funcName, "Enabling BlueBlobVision."); robot.vision.setBlueBlobVisionEnabled(true); - robot.vision.setBlueBlobAnnotateEnabled(true); } if (robot.vision.tensorFlowVision != null) diff --git a/TeamCode/src/main/java/teamcode/vision/Vision.java b/TeamCode/src/main/java/teamcode/vision/Vision.java index 384253c646da..f21391937319 100644 --- a/TeamCode/src/main/java/teamcode/vision/Vision.java +++ b/TeamCode/src/main/java/teamcode/vision/Vision.java @@ -123,11 +123,11 @@ public Vision(Robot robot, TrcDbgTrace tracer) robot.globalTracer.traceInfo(moduleName, "Starting ColorBlobVision..."); redBlobVision = new FtcVisionEocvColorBlob( "RedBlob", colorConversion, redBlobColorThresholds, redBlobFilterContourParams, - RobotParams.cameraRect, RobotParams.worldRect, tracer); + RobotParams.cameraRect, RobotParams.worldRect, true, tracer); redBlobProcessor = redBlobVision.getVisionProcessor(); blueBlobVision = new FtcVisionEocvColorBlob( "BlueBlob", colorConversion, blueBlobColorThresholds, blueBlobFilterContourParams, - RobotParams.cameraRect, RobotParams.worldRect, tracer); + RobotParams.cameraRect, RobotParams.worldRect, true, tracer); blueBlobProcessor = blueBlobVision.getVisionProcessor(); } @@ -136,8 +136,8 @@ public Vision(Robot robot, TrcDbgTrace tracer) robot.globalTracer.traceInfo(moduleName, "Starting TensorFlowVision..."); tensorFlowVision = new FtcVisionTensorFlow( null, TFOD_MODEL_ASSET, TARGET_LABELS, RobotParams.cameraRect, RobotParams.worldRect, tracer); - tensorFlowVision.getVisionProcessor().setMinResultConfidence(TFOD_MIN_CONFIDENCE); tensorFlowProcessor = tensorFlowVision.getVisionProcessor(); + tensorFlowProcessor.setMinResultConfidence(TFOD_MIN_CONFIDENCE); } VisionPortal.Builder builder = new VisionPortal.Builder(); @@ -210,14 +210,6 @@ public void setRedBlobVisionEnabled(boolean enabled) } } //setRedBlobVisionEnabled - public void setRedBlobAnnotateEnabled(boolean enabled) - { - if (redBlobProcessor != null) - { - redBlobProcessor.setAnnotateEnabled(enabled); - } - } //setRedBlobAnnotateEnabled - public void setBlueBlobVisionEnabled(boolean enabled) { if (blueBlobProcessor != null) @@ -226,14 +218,6 @@ public void setBlueBlobVisionEnabled(boolean enabled) } } //setBlueBlobVisionEnabled - public void setBlueBlobAnnotateEnabled(boolean enabled) - { - if (blueBlobProcessor != null) - { - blueBlobProcessor.setAnnotateEnabled(enabled); - } - } //setBlueBlobAnnotateEnabled - public void setTensorFlowVisionEnabled(boolean enabled) { if (tensorFlowProcessor != null) @@ -271,9 +255,6 @@ private void updateVisionLEDs(String label) { if (label != null && robot.blinkin != null) { -// robot.blinkin.setPatternState(BlinkinLEDs.LABEL_BOLT, false); -// robot.blinkin.setPatternState(BlinkinLEDs.LABEL_BULB, false); -// robot.blinkin.setPatternState(BlinkinLEDs.LABEL_PANEL, false); robot.blinkin.setPatternState(label, true, 1.0); } } //updateVisionLEDs @@ -287,27 +268,10 @@ private void updateVisionLEDs(String label) * if a has lower confidence than b. */ private int compareConfidence( - TrcVisionTargetInfo a, TrcVisionTargetInfo b) + TrcVisionTargetInfo a, + TrcVisionTargetInfo b) { return (int)((b.detectedObj.confidence - a.detectedObj.confidence)*100); } //compareConfidence - /** - * This method is called by the Arrays.sort to sort the target object by decreasing bottom Y. - * - * @param a specifies the first target - * @param b specifies the second target. - * @return negative value if a has smaller bottom Y than b, 0 if a and b have equal bottom Y, - * positive value if a has larger bottom Y than b. - */ - private int compareBottomY( - TrcVisionTargetInfo> a, - TrcVisionTargetInfo> b) - { - Rect aRect = a.detectedObj.getRect(); - Rect bRect = b.detectedObj.getRect(); - - return (bRect.y + bRect.height) - (aRect.y + aRect.height); - } //compareBottomY - } //class Vision