|
49 | 49 | * This OpMode illustrates using a camera to locate and drive towards a specific AprilTag. |
50 | 50 | * The code assumes a Holonomic (Mecanum or X Drive) Robot. |
51 | 51 | * |
| 52 | + * For an introduction to AprilTags, see the ftc-docs link below: |
| 53 | + * https://ftc-docs.firstinspires.org/en/latest/apriltag/vision_portal/apriltag_intro/apriltag-intro.html |
| 54 | + * |
| 55 | + * When an AprilTag in the TagLibrary is detected, the SDK provides location and orientation of the tag, relative to the camera. |
| 56 | + * This information is provided in the "ftcPose" member of the returned "detection", and is explained in the ftc-docs page linked below. |
| 57 | + * https://ftc-docs.firstinspires.org/apriltag-detection-values |
| 58 | + * |
52 | 59 | * The drive goal is to rotate to keep the Tag centered in the camera, while strafing to be directly in front of the tag, and |
53 | 60 | * driving towards the tag to achieve the desired distance. |
54 | 61 | * To reduce any motion blur (which will interrupt the detection process) the Camera exposure is reduced to a very low value (5mS) |
@@ -102,7 +109,7 @@ public class RobotAutoDriveToAprilTagOmni extends LinearOpMode |
102 | 109 | private DcMotor rightBackDrive = null; // Used to control the right back drive wheel |
103 | 110 |
|
104 | 111 | private static final boolean USE_WEBCAM = true; // Set true to use a webcam, or false for a phone camera |
105 | | - private static final int DESIRED_TAG_ID = 0; // Choose the tag you want to approach or set to -1 for ANY tag. |
| 112 | + private static final int DESIRED_TAG_ID = -1; // Choose the tag you want to approach or set to -1 for ANY tag. |
106 | 113 | private VisionPortal visionPortal; // Used to manage the video source. |
107 | 114 | private AprilTagProcessor aprilTag; // Used for managing the AprilTag detection process. |
108 | 115 | private AprilTagDetection desiredTag = null; // Used to hold the data for a detected AprilTag |
@@ -150,25 +157,33 @@ public class RobotAutoDriveToAprilTagOmni extends LinearOpMode |
150 | 157 | // Step through the list of detected tags and look for a matching tag |
151 | 158 | List<AprilTagDetection> currentDetections = aprilTag.getDetections(); |
152 | 159 | for (AprilTagDetection detection : currentDetections) { |
153 | | - if ((detection.metadata != null) && |
154 | | - ((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) ){ |
155 | | - targetFound = true; |
156 | | - desiredTag = detection; |
157 | | - break; // don't look any further. |
| 160 | + // Look to see if we have size info on this tag. |
| 161 | + if (detection.metadata != null) { |
| 162 | + // Check to see if we want to track towards this tag. |
| 163 | + if ((DESIRED_TAG_ID < 0) || (detection.id == DESIRED_TAG_ID)) { |
| 164 | + // Yes, we want to use this tag. |
| 165 | + targetFound = true; |
| 166 | + desiredTag = detection; |
| 167 | + break; // don't look any further. |
| 168 | + } else { |
| 169 | + // This tag is in the library, but we do not want to track it right now. |
| 170 | + telemetry.addData("Skipping", "Tag ID %d is not desired", detection.id); |
| 171 | + } |
158 | 172 | } else { |
159 | | - telemetry.addData("Unknown Target", "Tag ID %d is not in TagLibrary\n", detection.id); |
| 173 | + // This tag is NOT in the library, so we don't have enough information to track to it. |
| 174 | + telemetry.addData("Unknown", "Tag ID %d is not in TagLibrary", detection.id); |
160 | 175 | } |
161 | 176 | } |
162 | 177 |
|
163 | 178 | // Tell the driver what we see, and what to do. |
164 | 179 | if (targetFound) { |
165 | | - telemetry.addData(">","HOLD Left-Bumper to Drive to Target\n"); |
166 | | - telemetry.addData("Target", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name); |
| 180 | + telemetry.addData("\n>","HOLD Left-Bumper to Drive to Target\n"); |
| 181 | + telemetry.addData("Found", "ID %d (%s)", desiredTag.id, desiredTag.metadata.name); |
167 | 182 | telemetry.addData("Range", "%5.1f inches", desiredTag.ftcPose.range); |
168 | 183 | telemetry.addData("Bearing","%3.0f degrees", desiredTag.ftcPose.bearing); |
169 | 184 | telemetry.addData("Yaw","%3.0f degrees", desiredTag.ftcPose.yaw); |
170 | 185 | } else { |
171 | | - telemetry.addData(">","Drive using joysticks to find valid target\n"); |
| 186 | + telemetry.addData("\n>","Drive using joysticks to find valid target\n"); |
172 | 187 | } |
173 | 188 |
|
174 | 189 | // If Left Bumper is being pressed, AND we have found the desired target, Drive to target Automatically . |
@@ -243,6 +258,15 @@ private void initAprilTag() { |
243 | 258 | // Create the AprilTag processor by using a builder. |
244 | 259 | aprilTag = new AprilTagProcessor.Builder().build(); |
245 | 260 |
|
| 261 | + // Adjust Image Decimation to trade-off detection-range for detection-rate. |
| 262 | + // eg: Some typical detection data using a Logitech C920 WebCam |
| 263 | + // Decimation = 1 .. Detect 2" Tag from 10 feet away at 10 Frames per second |
| 264 | + // Decimation = 2 .. Detect 2" Tag from 6 feet away at 22 Frames per second |
| 265 | + // Decimation = 3 .. Detect 2" Tag from 4 feet away at 30 Frames Per Second |
| 266 | + // Decimation = 3 .. Detect 5" Tag from 10 feet away at 30 Frames Per Second |
| 267 | + // Note: Decimation can be changed on-the-fly to adapt during a match. |
| 268 | + aprilTag.setDecimation(2); |
| 269 | + |
246 | 270 | // Create the vision portal by using a builder. |
247 | 271 | if (USE_WEBCAM) { |
248 | 272 | visionPortal = new VisionPortal.Builder() |
|
0 commit comments