|
| 1 | +# |
| 2 | +# Copyright (c) FIRST and other WPILib contributors. |
| 3 | +# Open Source Software; you can modify and/or share it under the terms of |
| 4 | +# the WPILib BSD license file in the root directory of this project. |
| 5 | +# |
| 6 | + |
| 7 | + |
| 8 | +import ntcore |
| 9 | +import robotpy_apriltag |
| 10 | +from cscore import CameraServer |
| 11 | + |
| 12 | +import cv2 |
| 13 | +import numpy as np |
| 14 | + |
| 15 | + |
| 16 | +# |
| 17 | +# This code will work both on a RoboRIO and on other platforms. The exact mechanism |
| 18 | +# to run it differs depending on whether you’re on a RoboRIO or a coprocessor |
| 19 | +# |
| 20 | +# https://robotpy.readthedocs.io/en/stable/vision/code.html |
| 21 | + |
| 22 | + |
| 23 | +def main(): |
| 24 | + detector = robotpy_apriltag.AprilTagDetector() |
| 25 | + |
| 26 | + # Look for tag36h11, correct 7 error bits |
| 27 | + detector.addFamily("tag36h11", 7) |
| 28 | + |
| 29 | + # Set up Pose Estimator - parameters are for a Microsoft Lifecam HD-3000 |
| 30 | + # (https://www.chiefdelphi.com/t/wpilib-apriltagdetector-sample-code/421411/21) |
| 31 | + poseEstConfig = robotpy_apriltag.AprilTagPoseEstimator.Config( |
| 32 | + 0.1651, |
| 33 | + 699.3778103158814, |
| 34 | + 677.7161226393544, |
| 35 | + 345.6059345433618, |
| 36 | + 207.12741326228522, |
| 37 | + ) |
| 38 | + estimator = robotpy_apriltag.AprilTagPoseEstimator(poseEstConfig) |
| 39 | + |
| 40 | + # Get the UsbCamera from CameraServer |
| 41 | + camera = CameraServer.startAutomaticCapture() |
| 42 | + |
| 43 | + # Set the resolution |
| 44 | + camera.setResolution(640, 480) |
| 45 | + |
| 46 | + # Get a CvSink. This will capture Mats from the camera |
| 47 | + cvSink = CameraServer.getVideo() |
| 48 | + |
| 49 | + # Set up a CvSource. This will send images back to the Dashboard |
| 50 | + outputStream = CameraServer.putVideo("Detected", 640, 480) |
| 51 | + |
| 52 | + # Mats are very memory expensive. Let's reuse these. |
| 53 | + mat = np.zeros((480, 640, 3), dtype=np.uint8) |
| 54 | + grayMat = np.zeros(shape=(480, 640), dtype=np.uint8) |
| 55 | + |
| 56 | + # Instantiate once |
| 57 | + tags = [] # The list where the tags will be stored |
| 58 | + outlineColor = (0, 255, 0) # Color of Tag Outline |
| 59 | + crossColor = (0, 0, 25) # Color of Cross |
| 60 | + |
| 61 | + # Output the list to Network Tables |
| 62 | + tagsTable = ntcore.NetworkTableInstance.getDefault().getTable("apriltags") |
| 63 | + pubTags = tagsTable.getIntegerArrayTopic("tags").publish() |
| 64 | + |
| 65 | + while True: |
| 66 | + # Tell the CvSink to grab a frame from the camera and put it |
| 67 | + # in the source mat. If there is an error notify the output. |
| 68 | + if cvSink.grabFrame(mat) == 0: |
| 69 | + # Send the output frame the error |
| 70 | + outputStream.notifyError(cvSink.getError()) |
| 71 | + |
| 72 | + # Skip the rest of the current iteration |
| 73 | + continue |
| 74 | + |
| 75 | + cv2.cvtColor(mat, cv2.COLOR_RGB2GRAY, dst=grayMat) |
| 76 | + |
| 77 | + detections = detector.detect(grayMat) |
| 78 | + |
| 79 | + tags.clear() |
| 80 | + |
| 81 | + for detection in detections: |
| 82 | + # Remember the tag we saw |
| 83 | + tags.append(detection.getId()) |
| 84 | + |
| 85 | + # Draw lines around the tag |
| 86 | + for i in range(4): |
| 87 | + j = (i + 1) % 4 |
| 88 | + point1 = (int(detection.getCorner(i).x), int(detection.getCorner(i).y)) |
| 89 | + point2 = (int(detection.getCorner(j).x), int(detection.getCorner(j).y)) |
| 90 | + mat = cv2.line(mat, point1, point2, outlineColor, 2) |
| 91 | + |
| 92 | + # Mark the center of the tag |
| 93 | + cx = int(detection.getCenter().x) |
| 94 | + cy = int(detection.getCenter().y) |
| 95 | + ll = 10 |
| 96 | + mat = cv2.line( |
| 97 | + mat, |
| 98 | + (cx - ll, cy), |
| 99 | + (cx + ll, cy), |
| 100 | + crossColor, |
| 101 | + 2, |
| 102 | + ) |
| 103 | + mat = cv2.line( |
| 104 | + mat, |
| 105 | + (cx, cy - ll), |
| 106 | + (cx, cy + ll), |
| 107 | + crossColor, |
| 108 | + 2, |
| 109 | + ) |
| 110 | + |
| 111 | + # Identify the tag |
| 112 | + mat = cv2.putText( |
| 113 | + mat, |
| 114 | + str(detection.getId()), |
| 115 | + (cx + ll, cy), |
| 116 | + cv2.FONT_HERSHEY_SIMPLEX, |
| 117 | + 1, |
| 118 | + crossColor, |
| 119 | + 3, |
| 120 | + ) |
| 121 | + |
| 122 | + # Determine Tag Pose |
| 123 | + pose = estimator.estimate(detection) |
| 124 | + |
| 125 | + # put pose into dashboard |
| 126 | + rot = pose.rotation() |
| 127 | + tagsTable.getEntry(f"pose_{detection.getId()}").setDoubleArray( |
| 128 | + [pose.X(), pose.Y(), pose.Z(), rot.X(), rot.Y(), rot.Z()] |
| 129 | + ) |
| 130 | + |
| 131 | + # Put List of Tags onto Dashboard |
| 132 | + pubTags.set(tags) |
| 133 | + |
| 134 | + # Give output stream a new image to display |
| 135 | + outputStream.putFrame(mat) |
| 136 | + |
| 137 | + # The camera code will be killed when the robot.py program exits. If you wish to perform cleanup, |
| 138 | + # you should register an atexit handler. The child process will NOT be launched when running the robot code in |
| 139 | + # simulation or unit testing mode |
0 commit comments