diff --git a/TeamCode/src/main/java/TrcCommonLib b/TeamCode/src/main/java/TrcCommonLib index 4eb988ed1c2b..95fde8b7a4be 160000 --- a/TeamCode/src/main/java/TrcCommonLib +++ b/TeamCode/src/main/java/TrcCommonLib @@ -1 +1 @@ -Subproject commit 4eb988ed1c2be6086b30e83e33d4f8c51d8b1555 +Subproject commit 95fde8b7a4be2f32ec23b70b8d687ed5c0fef278 diff --git a/TeamCode/src/main/java/TrcFtcLib b/TeamCode/src/main/java/TrcFtcLib index 42374bd3acec..35a96db8aa49 160000 --- a/TeamCode/src/main/java/TrcFtcLib +++ b/TeamCode/src/main/java/TrcFtcLib @@ -1 +1 @@ -Subproject commit 42374bd3aceca52fd2aeef15e28a4c6f60d1e230 +Subproject commit 35a96db8aa49d4765b704bbac6c3371622be1c79 diff --git a/TeamCode/src/main/java/TrcFtcSamples b/TeamCode/src/main/java/TrcFtcSamples index 1a27afdb4aa6..6cd4fdd561df 160000 --- a/TeamCode/src/main/java/TrcFtcSamples +++ b/TeamCode/src/main/java/TrcFtcSamples @@ -1 +1 @@ -Subproject commit 1a27afdb4aa69c4f4b1bf1f6a079718bc5f47f24 +Subproject commit 6cd4fdd561df498ea2c51d9c7637fb2f923c12f5 diff --git a/TeamCode/src/main/java/teamcode/FtcTeleOp.java b/TeamCode/src/main/java/teamcode/FtcTeleOp.java index e99040eef05e..773f9845b0e2 100644 --- a/TeamCode/src/main/java/teamcode/FtcTeleOp.java +++ b/TeamCode/src/main/java/teamcode/FtcTeleOp.java @@ -32,7 +32,6 @@ import TrcFtcLib.ftclib.FtcGamepad; import TrcFtcLib.ftclib.FtcOpMode; import teamcode.drivebases.SwerveDrive; -import teamcode.subsystems.BlinkinLEDs; /** * This class contains the TeleOp Mode program. @@ -80,6 +79,7 @@ public void robotInit() operatorGamepad = new FtcGamepad("OperatorGamepad", gamepad2, this::operatorButtonEvent); driverGamepad.setYInverted(true); operatorGamepad.setYInverted(true); + setDriveOrientation(TrcDriveBase.DriveOrientation.ROBOT); } //robotInit // @@ -107,7 +107,6 @@ public void startMode(TrcRobot.RunMode prevMode, TrcRobot.RunMode nextMode) // Tell robot object opmode is about to start so it can do the necessary start initialization for the mode. // robot.startMode(nextMode); - updateDriveModeLEDs(); } //startMode /** @@ -180,33 +179,22 @@ public void periodic(double elapsedTime, boolean slowPeriodicLoop) } //periodic /** - * This method updates the blinkin LEDs to show the drive orientation mode. + * This method sets the drive orientation mode and updates the LED to indicate so. + * + * @param orientation specifies the drive orientation (FIELD, ROBOT, INVERTED). */ - private void updateDriveModeLEDs() + public void setDriveOrientation(TrcDriveBase.DriveOrientation orientation) { - if (robot.blinkin != null && robot.robotDrive != null) + if (robot.robotDrive != null) { - TrcDriveBase.DriveOrientation orientation = robot.robotDrive.driveBase.getDriveOrientation(); - - robot.blinkin.setPatternState(BlinkinLEDs.DRIVE_ORIENTATION_FIELD, false); - robot.blinkin.setPatternState(BlinkinLEDs.DRIVE_ORIENTATION_ROBOT, false); - robot.blinkin.setPatternState(BlinkinLEDs.DRIVE_ORIENTATION_INVERTED, false); - switch (orientation) + robot.robotDrive.driveBase.setDriveOrientation( + orientation, orientation == TrcDriveBase.DriveOrientation.FIELD); + if (robot.blinkin != null) { - case FIELD: - robot.blinkin.setPatternState(BlinkinLEDs.DRIVE_ORIENTATION_FIELD, true); - break; - - case ROBOT: - robot.blinkin.setPatternState(BlinkinLEDs.DRIVE_ORIENTATION_ROBOT, true); - break; - - case INVERTED: - robot.blinkin.setPatternState(BlinkinLEDs.DRIVE_ORIENTATION_INVERTED, true); - break; + robot.blinkin.setDriveOrientation(orientation); } } - } //updateDriveModeLEDs + } //setDriveOrientation // // Implements TrcGameController.ButtonHandler interface. @@ -222,10 +210,6 @@ private void updateDriveModeLEDs() public void driverButtonEvent(TrcGameController gamepad, int button, boolean pressed) { robot.dashboard.displayPrintf(7, "%s: %04x->%s", gamepad, button, pressed? "Pressed": "Released"); - if (robot.robotDrive != null) - { - robot.dashboard.displayPrintf(8, "Drive Mode:%s", robot.robotDrive.driveBase.getDriveOrientation()); - } switch (button) { @@ -256,17 +240,14 @@ public void driverButtonEvent(TrcGameController gamepad, int button, boolean pre // Toggle between field or robot oriented driving, only applicable for holonomic drive base. if (pressed && robot.robotDrive != null && robot.robotDrive.driveBase.supportsHolonomicDrive()) { - TrcDriveBase.DriveOrientation orientation = robot.robotDrive.driveBase.getDriveOrientation(); - if (orientation != TrcDriveBase.DriveOrientation.FIELD) + if (robot.robotDrive.driveBase.getDriveOrientation() != TrcDriveBase.DriveOrientation.FIELD) { - orientation = TrcDriveBase.DriveOrientation.FIELD; + setDriveOrientation(TrcDriveBase.DriveOrientation.FIELD); } else { - orientation = TrcDriveBase.DriveOrientation.ROBOT; + setDriveOrientation(TrcDriveBase.DriveOrientation.ROBOT); } - robot.robotDrive.driveBase.setDriveOrientation(orientation, true); - updateDriveModeLEDs(); } break; diff --git a/TeamCode/src/main/java/teamcode/FtcTest.java b/TeamCode/src/main/java/teamcode/FtcTest.java index 4e899abea8c3..4655628dec75 100644 --- a/TeamCode/src/main/java/teamcode/FtcTest.java +++ b/TeamCode/src/main/java/teamcode/FtcTest.java @@ -49,6 +49,7 @@ import TrcFtcLib.ftclib.FtcVisionTensorFlow; import teamcode.drivebases.RobotDrive; import teamcode.drivebases.SwerveDrive; +import teamcode.subsystems.BlinkinLEDs; /** * This class contains the Test Mode program. It extends FtcTeleOp so that we can teleop control the robot for @@ -956,6 +957,10 @@ private void doVisionTest() robot.vision.aprilTagVision.getBestDetectedTargetInfo(null); robot.dashboard.displayPrintf( lineNum++, "AprilTag: %s", aprilTagInfo != null? aprilTagInfo: "Not found."); + if (robot.blinkin != null) + { + robot.blinkin.setPatternState(BlinkinLEDs.APRIL_TAG, aprilTagInfo != null); + } } if (robot.vision.redBlobVision != null) @@ -965,6 +970,10 @@ private void doVisionTest() robot.vision.redBlobVision.getBestDetectedTargetInfo(null, null, 0.0, 0.0); robot.dashboard.displayPrintf( lineNum++, "RedBlob: %s", redBlobInfo != null? redBlobInfo: "Not found."); + if (robot.blinkin != null) + { + robot.blinkin.setPatternState(BlinkinLEDs.RED_BLOB, redBlobInfo != null); + } } if (robot.vision.blueBlobVision != null) @@ -974,6 +983,10 @@ private void doVisionTest() robot.vision.blueBlobVision.getBestDetectedTargetInfo(null, null, 0.0, 0.0); robot.dashboard.displayPrintf( lineNum++, "BlueBlob: %s", blueBlobInfo != null? blueBlobInfo: "Not found."); + if (robot.blinkin != null) + { + robot.blinkin.setPatternState(BlinkinLEDs.BLUE_BLOB, blueBlobInfo != null); + } } if (robot.vision.tensorFlowVision != null) @@ -982,6 +995,10 @@ private void doVisionTest() robot.vision.tensorFlowVision.getBestDetectedTargetInfo(null, null, null, 0.0, 0.0); robot.dashboard.displayPrintf( lineNum++, "TensorFlow: %s", tensorFlowInfo != null? tensorFlowInfo: "Not found."); + if (robot.blinkin != null) + { + robot.blinkin.setPatternState(BlinkinLEDs.TENSOR_FLOW, tensorFlowInfo != null); + } } } } //doVisionTest diff --git a/TeamCode/src/main/java/teamcode/Robot.java b/TeamCode/src/main/java/teamcode/Robot.java index 17823bf4d602..41389390410f 100644 --- a/TeamCode/src/main/java/teamcode/Robot.java +++ b/TeamCode/src/main/java/teamcode/Robot.java @@ -31,7 +31,6 @@ import TrcFtcLib.ftclib.FtcDashboard; import TrcFtcLib.ftclib.FtcMatchInfo; import TrcFtcLib.ftclib.FtcOpMode; -import TrcFtcLib.ftclib.FtcRevBlinkin; import TrcFtcLib.ftclib.FtcRobotBattery; import teamcode.drivebases.MecanumDrive; import teamcode.drivebases.RobotDrive; @@ -59,7 +58,7 @@ public class Robot // // Sensors and indicators. // - public FtcRevBlinkin blinkin; + public BlinkinLEDs blinkin; public FtcRobotBattery battery; // // Subsystems. diff --git a/TeamCode/src/main/java/teamcode/subsystems/BlinkinLEDs.java b/TeamCode/src/main/java/teamcode/subsystems/BlinkinLEDs.java index 51a9d83f978b..7994fedff5f5 100644 --- a/TeamCode/src/main/java/teamcode/subsystems/BlinkinLEDs.java +++ b/TeamCode/src/main/java/teamcode/subsystems/BlinkinLEDs.java @@ -22,6 +22,7 @@ package teamcode.subsystems; +import TrcCommonLib.trclib.TrcDriveBase; import TrcCommonLib.trclib.TrcRevBlinkin; import TrcFtcLib.ftclib.FtcRevBlinkin; @@ -32,13 +33,14 @@ public class BlinkinLEDs extends FtcRevBlinkin { // LED pattern names. - public static final String IMAGE1_NAME = "Image1"; - public static final String IMAGE2_NAME = "Image2"; - public static final String IMAGE3_NAME = "Image3"; - public static final String IMAGE4_NAME = "Image4"; + public static final String APRIL_TAG = "AprilTag"; + public static final String RED_BLOB = "RedBlob"; + public static final String BLUE_BLOB = "BlueBlob"; + public static final String TENSOR_FLOW = "TensorFlow"; public static final String DRIVE_ORIENTATION_FIELD = "FieldMode"; public static final String DRIVE_ORIENTATION_ROBOT = "RobotMode"; public static final String DRIVE_ORIENTATION_INVERTED = "InvertedMode"; + public static final String OFF_PATTERN = "Off"; /** * Constructor: Create an instance of the object. @@ -51,16 +53,46 @@ public BlinkinLEDs(String instanceName) // LED Patterns are sorted in decreasing priority order. final TrcRevBlinkin.Pattern[] ledPatternPriorities = { // Highest priority. - new TrcRevBlinkin.Pattern(IMAGE1_NAME, RevLedPattern.FixedLightChaseRed), - new TrcRevBlinkin.Pattern(IMAGE2_NAME, RevLedPattern.FixedLightChaseBlue), - new TrcRevBlinkin.Pattern(IMAGE3_NAME, RevLedPattern.FixedBreathRed), - new TrcRevBlinkin.Pattern(IMAGE4_NAME, RevLedPattern.FixedBreathBlue), - new TrcRevBlinkin.Pattern(DRIVE_ORIENTATION_FIELD, TrcRevBlinkin.RevLedPattern.SolidViolet), - new TrcRevBlinkin.Pattern(DRIVE_ORIENTATION_ROBOT, TrcRevBlinkin.RevLedPattern.SolidWhite), - new TrcRevBlinkin.Pattern(DRIVE_ORIENTATION_INVERTED, TrcRevBlinkin.RevLedPattern.SolidGray) + new TrcRevBlinkin.Pattern(APRIL_TAG, RevLedPattern.SolidAqua), + new TrcRevBlinkin.Pattern(RED_BLOB, RevLedPattern.SolidRed), + new TrcRevBlinkin.Pattern(BLUE_BLOB, RevLedPattern.SolidBlue), + new TrcRevBlinkin.Pattern(TENSOR_FLOW, RevLedPattern.SolidYellow), + new TrcRevBlinkin.Pattern(DRIVE_ORIENTATION_FIELD, RevLedPattern.SolidViolet), + new TrcRevBlinkin.Pattern(DRIVE_ORIENTATION_ROBOT, RevLedPattern.SolidWhite), + new TrcRevBlinkin.Pattern(DRIVE_ORIENTATION_INVERTED, RevLedPattern.SolidGray), + new TrcRevBlinkin.Pattern(OFF_PATTERN, RevLedPattern.SolidBlack) // Lowest priority. }; setPatternPriorities(ledPatternPriorities); } //BlinkinLEDs + /** + * This method sets the LED to indicate the drive orientation mode of the robot. + * + * @param orientation specifies the drive orientation mode. + */ + public void setDriveOrientation(TrcDriveBase.DriveOrientation orientation) + { + switch (orientation) + { + case INVERTED: + setPatternState(DRIVE_ORIENTATION_INVERTED, true); + setPatternState(DRIVE_ORIENTATION_ROBOT, false); + setPatternState(DRIVE_ORIENTATION_FIELD, false); + break; + + case ROBOT: + setPatternState(DRIVE_ORIENTATION_INVERTED, false); + setPatternState(DRIVE_ORIENTATION_ROBOT, true); + setPatternState(DRIVE_ORIENTATION_FIELD, false); + break; + + case FIELD: + setPatternState(DRIVE_ORIENTATION_INVERTED, false); + setPatternState(DRIVE_ORIENTATION_ROBOT, false); + setPatternState(DRIVE_ORIENTATION_FIELD, true); + break; + } + } //setDriveOrientation + } //class BlinkinLEDs diff --git a/TeamCode/src/main/java/teamcode/vision/Vision.java b/TeamCode/src/main/java/teamcode/vision/Vision.java index f21391937319..73e39f97c4a0 100644 --- a/TeamCode/src/main/java/teamcode/vision/Vision.java +++ b/TeamCode/src/main/java/teamcode/vision/Vision.java @@ -22,24 +22,23 @@ package teamcode.vision; -import android.util.Size; - import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; -import org.firstinspires.ftc.vision.VisionPortal; +import org.firstinspires.ftc.vision.VisionProcessor; import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; import org.firstinspires.ftc.vision.tfod.TfodProcessor; -import org.opencv.core.Rect; import org.opencv.imgproc.Imgproc; +import java.util.ArrayList; + import TrcCommonLib.trclib.TrcDbgTrace; import TrcCommonLib.trclib.TrcOpenCvColorBlobPipeline; -import TrcCommonLib.trclib.TrcOpenCvDetector; import TrcCommonLib.trclib.TrcVisionTargetInfo; import TrcFtcLib.ftclib.FtcEocvColorBlobProcessor; import TrcFtcLib.ftclib.FtcOpMode; +import TrcFtcLib.ftclib.FtcVision; import TrcFtcLib.ftclib.FtcVisionAprilTag; import TrcFtcLib.ftclib.FtcVisionEocvColorBlob; import TrcFtcLib.ftclib.FtcVisionTensorFlow; @@ -57,29 +56,19 @@ public class Vision private static final int colorConversion = Imgproc.COLOR_BGRA2BGR; private static final double[] redBlobColorThresholds = {100.0, 255.0, 0.0, 100.0, 0.0, 60.0}; private static final double[] blueBlobColorThresholds = {0.0, 60.0, 0.0, 100.0, 100, 255.0}; - private static final TrcOpenCvColorBlobPipeline.FilterContourParams redBlobFilterContourParams = - new TrcOpenCvColorBlobPipeline.FilterContourParams() - .setMinArea(10000.0) - .setMinPerimeter(200.0) - .setWidthRange(100.0, 1000.0) - .setHeightRange(100.0, 1000.0) - .setSolidityRange(0.0, 100.0) - .setVerticesRange(0.0, 1000.0) - .setAspectRatioRange(0.0, 1000.0); - private static final TrcOpenCvColorBlobPipeline.FilterContourParams blueBlobFilterContourParams = + private static final TrcOpenCvColorBlobPipeline.FilterContourParams colorBlobFilterContourParams = new TrcOpenCvColorBlobPipeline.FilterContourParams() - .setMinArea(10000.0) - .setMinPerimeter(200.0) - .setWidthRange(100.0, 1000.0) - .setHeightRange(100.0, 1000.0) + .setMinArea(1000.0) + .setMinPerimeter(100.0) + .setWidthRange(10.0, 1000.0) + .setHeightRange(10.0, 1000.0) .setSolidityRange(0.0, 100.0) .setVerticesRange(0.0, 1000.0) - .setAspectRatioRange(0.0, 1000.0); - private static final String TFOD_MODEL_ASSET = "CenterStage.tflite"; + .setAspectRatioRange(0.0, 10.0); + private static final String TFOD_MODEL_ASSET = "MyObject.tflite"; private static final float TFOD_MIN_CONFIDENCE = 0.75f; - public static final String[] TARGET_LABELS = {}; + public static final String[] TFOD_TARGET_LABELS = {"MyObject"}; - private final Robot robot; public FtcVisionAprilTag aprilTagVision; private AprilTagProcessor aprilTagProcessor; public FtcVisionEocvColorBlob redBlobVision; @@ -88,12 +77,10 @@ public class Vision private FtcEocvColorBlobProcessor blueBlobProcessor; public FtcVisionTensorFlow tensorFlowVision; private TfodProcessor tensorFlowProcessor; - private final VisionPortal visionPortal; + private final FtcVision vision; /** - * Constructor: Create an instance of the object. Vision is required by both Vuforia and TensorFlow and must be - * instantiated if either is used. However, to use either Vuforia or TensorFlow, one must explicitly initialize - * them by calling the initVuforia or initTensorFlow methods respectively. + * Constructor: Create an instance of the object. * * @param robot specifies the robot object. * @param tracer specifies the tracer for trace info, null if none provided. @@ -101,8 +88,8 @@ public class Vision public Vision(Robot robot, TrcDbgTrace tracer) { FtcOpMode opMode = FtcOpMode.getInstance(); + ArrayList visionProcessorList = new ArrayList<>(); - this.robot = robot; if (RobotParams.Preferences.useAprilTagVision) { robot.globalTracer.traceInfo(moduleName, "Starting AprilTagVision..."); @@ -116,148 +103,146 @@ public Vision(Robot robot, TrcDbgTrace tracer) .setOutputUnits(DistanceUnit.INCH, AngleUnit.DEGREES); aprilTagVision = new FtcVisionAprilTag(aprilTagParams, AprilTagProcessor.TagFamily.TAG_36h11, tracer); aprilTagProcessor = aprilTagVision.getVisionProcessor(); + visionProcessorList.add(aprilTagProcessor); } if (RobotParams.Preferences.useColorBlobVision) { robot.globalTracer.traceInfo(moduleName, "Starting ColorBlobVision..."); + redBlobVision = new FtcVisionEocvColorBlob( - "RedBlob", colorConversion, redBlobColorThresholds, redBlobFilterContourParams, + "RedBlob", colorConversion, redBlobColorThresholds, colorBlobFilterContourParams, RobotParams.cameraRect, RobotParams.worldRect, true, tracer); redBlobProcessor = redBlobVision.getVisionProcessor(); + visionProcessorList.add(redBlobProcessor); + blueBlobVision = new FtcVisionEocvColorBlob( - "BlueBlob", colorConversion, blueBlobColorThresholds, blueBlobFilterContourParams, + "BlueBlob", colorConversion, blueBlobColorThresholds, colorBlobFilterContourParams, RobotParams.cameraRect, RobotParams.worldRect, true, tracer); blueBlobProcessor = blueBlobVision.getVisionProcessor(); + visionProcessorList.add(blueBlobProcessor); } if (RobotParams.Preferences.useTensorFlowVision) { robot.globalTracer.traceInfo(moduleName, "Starting TensorFlowVision..."); tensorFlowVision = new FtcVisionTensorFlow( - null, TFOD_MODEL_ASSET, TARGET_LABELS, RobotParams.cameraRect, RobotParams.worldRect, tracer); + null, TFOD_MODEL_ASSET, TFOD_TARGET_LABELS, RobotParams.cameraRect, RobotParams.worldRect, tracer); tensorFlowProcessor = tensorFlowVision.getVisionProcessor(); tensorFlowProcessor.setMinResultConfidence(TFOD_MIN_CONFIDENCE); + visionProcessorList.add(tensorFlowProcessor); } - VisionPortal.Builder builder = new VisionPortal.Builder(); - // Set the camera (webcam vs. built-in RC phone camera). - if (RobotParams.Preferences.useWebCam) - { - builder.setCamera(opMode.hardwareMap.get(WebcamName.class, RobotParams.HWNAME_WEBCAM)); - } - else - { - builder.setCamera( - RobotParams.Preferences.useBuiltinCamBack? BuiltinCameraDirection.BACK: BuiltinCameraDirection.FRONT); - } - builder.setCameraResolution(new Size(RobotParams.CAM_IMAGE_WIDTH, RobotParams.CAM_IMAGE_HEIGHT)); - - if (RobotParams.Preferences.showVisionView) - { - - builder.enableLiveView(true); - builder.setAutoStopLiveView(true); - //Set the stream format; MJPEG uses less bandwidth than default YUY2. - // builder.setStreamFormat(VisionPortal.StreamFormat.YUY2); - } - else - { - builder.enableLiveView(false); - } - - if (aprilTagProcessor != null) - { - builder.addProcessor(aprilTagProcessor); - } - - if (redBlobProcessor != null) - { - builder.addProcessor(redBlobProcessor); - } - - if (blueBlobProcessor != null) - { - builder.addProcessor(blueBlobProcessor); - } - - if (tensorFlowProcessor != null) - { - builder.addProcessor(tensorFlowProcessor); - } - // Build the Vision Portal, using the above settings. - visionPortal = builder.build(); - // Disable all vision processor until they are needed. + VisionProcessor[] visionProcessors = new VisionProcessor[visionProcessorList.size()]; + visionProcessorList.toArray(visionProcessors); + vision = RobotParams.Preferences.useWebCam ? + new FtcVision( + opMode.hardwareMap.get(WebcamName.class, RobotParams.HWNAME_WEBCAM), + RobotParams.CAM_IMAGE_WIDTH, RobotParams.CAM_IMAGE_HEIGHT, + RobotParams.Preferences.showVisionView, visionProcessors) : + new FtcVision( + RobotParams.Preferences.useBuiltinCamBack ? + BuiltinCameraDirection.BACK : BuiltinCameraDirection.FRONT, + RobotParams.CAM_IMAGE_WIDTH, RobotParams.CAM_IMAGE_HEIGHT, + RobotParams.Preferences.showVisionView, visionProcessors); + // Disable all vision processors until they are needed. setAprilTagVisionEnabled(false); setRedBlobVisionEnabled(false); setBlueBlobVisionEnabled(false); setTensorFlowVisionEnabled(false); } //Vision + /** + * This method enables/disables AprilTag vision. + * + * @param enabled specifies true to enable, false to disable. + */ public void setAprilTagVisionEnabled(boolean enabled) { if (aprilTagProcessor != null) { - visionPortal.setProcessorEnabled(aprilTagProcessor, enabled); + vision.setProcessorEnabled(aprilTagProcessor, enabled); } } //setAprilTagVisionEnabled + /** + * This method enables/disables RedBlob vision. + * + * @param enabled specifies true to enable, false to disable. + */ public void setRedBlobVisionEnabled(boolean enabled) { if (redBlobProcessor != null) { - visionPortal.setProcessorEnabled(redBlobProcessor, enabled); + vision.setProcessorEnabled(redBlobProcessor, enabled); } } //setRedBlobVisionEnabled + /** + * This method enables/disables BlueBlob vision. + * + * @param enabled specifies true to enable, false to disable. + */ public void setBlueBlobVisionEnabled(boolean enabled) { if (blueBlobProcessor != null) { - visionPortal.setProcessorEnabled(blueBlobProcessor, enabled); + vision.setProcessorEnabled(blueBlobProcessor, enabled); } } //setBlueBlobVisionEnabled + /** + * This method enables/disables TensorFlow vision. + * + * @param enabled specifies true to enable, false to disable. + */ public void setTensorFlowVisionEnabled(boolean enabled) { if (tensorFlowProcessor != null) { - visionPortal.setProcessorEnabled(tensorFlowProcessor, enabled); + vision.setProcessorEnabled(tensorFlowProcessor, enabled); } } //setTensorFlowVisionEnabled - public boolean isAprilTagVisionEabled() + /** + * This method checks if AprilTag vision is enabled. + * + * @return true if enabled, false if disabled. + */ + public boolean isAprilTagVisionEnabled() { - return aprilTagProcessor != null && visionPortal.getProcessorEnabled(aprilTagProcessor); + return aprilTagProcessor != null && vision.isVisionProcessorEnabled(aprilTagProcessor); } //isAprilTagVisionEnabled - public boolean isRedBlobVisionEabled() + /** + * This method checks if RedBlob vision is enabled. + * + * @return true if enabled, false if disabled. + */ + public boolean isRedBlobVisionEnabled() { - return redBlobProcessor != null && visionPortal.getProcessorEnabled(redBlobProcessor); + return redBlobProcessor != null && vision.isVisionProcessorEnabled(redBlobProcessor); } //isRedBlobVisionEnabled - public boolean isBlueBlobVisionEabled() + /** + * This method checks if BlueBlob vision is enabled. + * + * @return true if enabled, false if disabled. + */ + public boolean isBlueBlobVisionEnabled() { - return blueBlobProcessor != null && visionPortal.getProcessorEnabled(blueBlobProcessor); + return blueBlobProcessor != null && vision.isVisionProcessorEnabled(blueBlobProcessor); } //isBlueBlobVisionEnabled - public boolean isTensorFlowVisionEabled() - { - return tensorFlowProcessor != null && visionPortal.getProcessorEnabled(tensorFlowProcessor); - } //isTensorFlowVisionEnabled - /** - * This method updates the LED state to show the vision detected object. + * This method checks if TensorFlow vision is enabled. * - * @param label specifies the detected object. + * @return true if enabled, false if disabled. */ - private void updateVisionLEDs(String label) + public boolean isTensorFlowVisionEnabled() { - if (label != null && robot.blinkin != null) - { - robot.blinkin.setPatternState(label, true, 1.0); - } - } //updateVisionLEDs + return tensorFlowProcessor != null && vision.isVisionProcessorEnabled(tensorFlowProcessor); + } //isTensorFlowVisionEnabled /** * This method is called by the Arrays.sort to sort the target object by decreasing confidence.