/* Copyright (c) 2023 FIRST. All rights reserved. * * Redistribution and use in source and binary forms, with or without modification, * are permitted (subject to the limitations in the disclaimer below) provided that * the following conditions are met: * * Redistributions of source code must retain the above copyright notice, this list * of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above copyright notice, this * list of conditions and the following disclaimer in the documentation and/or * other materials provided with the distribution. * * Neither the name of FIRST nor the names of its contributors may be used to endorse or * promote products derived from this software without specific prior written permission. * * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */ package org.firstinspires.ftc.robotcontroller.external.samples; import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import org.firstinspires.ftc.robotcore.external.hardware.camera.BuiltinCameraDirection; import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; import org.firstinspires.ftc.vision.VisionPortal; import org.firstinspires.ftc.vision.apriltag.AprilTagDetection; import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor; import java.util.List; /* * This OpMode illustrates the basics of AprilTag recognition and pose estimation, using * the easy way. * * Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name. * Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list. */ @TeleOp(name = "Concept: AprilTag Easy", group = "Concept") @Disabled public class ConceptAprilTagEasy extends LinearOpMode { private static final boolean USE_WEBCAM = true; // true for webcam, false for phone camera /** * The variable to store our instance of the AprilTag processor. */ private AprilTagProcessor aprilTag; /** * The variable to store our instance of the vision portal. */ private VisionPortal visionPortal; @Override public void runOpMode() { initAprilTag(); // Wait for the DS start button to be touched. telemetry.addData("DS preview on/off", "3 dots, Camera Stream"); telemetry.addData(">", "Touch Play to start OpMode"); telemetry.update(); waitForStart(); if (opModeIsActive()) { while (opModeIsActive()) { telemetryAprilTag(); // Push telemetry to the Driver Station. telemetry.update(); // Save CPU resources; can resume streaming when needed. if (gamepad1.dpad_down) { visionPortal.stopStreaming(); } else if (gamepad1.dpad_up) { visionPortal.resumeStreaming(); } // Share the CPU. sleep(20); } } // Save more CPU resources when camera is no longer needed. visionPortal.close(); } // end method runOpMode() /** * Initialize the AprilTag processor. */ private void initAprilTag() { // Create the AprilTag processor the easy way. aprilTag = AprilTagProcessor.easyCreateWithDefaults(); // Create the vision portal the easy way. if (USE_WEBCAM) { visionPortal = VisionPortal.easyCreateWithDefaults( hardwareMap.get(WebcamName.class, "Webcam 1"), aprilTag); } else { visionPortal = VisionPortal.easyCreateWithDefaults( BuiltinCameraDirection.BACK, aprilTag); } } // end method initAprilTag() /** * Add telemetry about AprilTag detections. */ private void telemetryAprilTag() { List currentDetections = aprilTag.getDetections(); telemetry.addData("# AprilTags Detected", currentDetections.size()); // Step through the list of detections and display info for each one. for (AprilTagDetection detection : currentDetections) { if (detection.metadata != null) { telemetry.addLine(String.format("\n==== (ID %d) %s", detection.id, detection.metadata.name)); telemetry.addLine(String.format("XYZ %6.1f %6.1f %6.1f (inch)", detection.ftcPose.x, detection.ftcPose.y, detection.ftcPose.z)); telemetry.addLine(String.format("PRY %6.1f %6.1f %6.1f (deg)", detection.ftcPose.pitch, detection.ftcPose.roll, detection.ftcPose.yaw)); telemetry.addLine(String.format("RBE %6.1f %6.1f %6.1f (inch, deg, deg)", detection.ftcPose.range, detection.ftcPose.bearing, detection.ftcPose.elevation)); } else { telemetry.addLine(String.format("\n==== (ID %d) Unknown", detection.id)); telemetry.addLine(String.format("Center %6.0f %6.0f (pixels)", detection.center.x, detection.center.y)); } } // end for() loop // Add "key" information to telemetry telemetry.addLine("\nkey:\nXYZ = X (Right), Y (Forward), Z (Up) dist."); telemetry.addLine("PRY = Pitch, Roll & Yaw (XYZ Rotation)"); telemetry.addLine("RBE = Range, Bearing & Elevation"); } // end method telemetryAprilTag() } // end class