|
23 | 23 | def main(): |
24 | 24 | detector = robotpy_apriltag.AprilTagDetector() |
25 | 25 |
|
26 | | - # Look for tag36h11, correct 3 error bits |
27 | | - detector.addFamily("tag36h11", 3) |
| 26 | + # look for tag36h11, correct 1 error bit (hamming distance 1) |
| 27 | + # hamming 1 allocates 781KB, 2 allocates 27.4 MB, 3 allocates 932 MB |
| 28 | + # max of 1 recommended for RoboRIO 1, while hamming 2 is feasible on the RoboRIO 2 |
| 29 | + detector.addFamily("tag36h11", 1) |
28 | 30 |
|
29 | 31 | # Set up Pose Estimator - parameters are for a Microsoft Lifecam HD-3000 |
30 | 32 | # (https://www.chiefdelphi.com/t/wpilib-apriltagdetector-sample-code/421411/21) |
@@ -54,85 +56,96 @@ def main(): |
54 | 56 | grayMat = np.zeros(shape=(480, 640), dtype=np.uint8) |
55 | 57 |
|
56 | 58 | # 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 |
| 59 | + tags = [] |
| 60 | + outlineColor = (0, 255, 0) |
| 61 | + crossColor = (0, 0, 255) |
60 | 62 |
|
61 | 63 | # Output the list to Network Tables |
62 | 64 | tagsTable = ntcore.NetworkTableInstance.getDefault().getTable("apriltags") |
63 | 65 | pubTags = tagsTable.getIntegerArrayTopic("tags").publish() |
64 | 66 |
|
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) |
| 67 | + try: |
| 68 | + while True: |
| 69 | + # Tell the CvSink to grab a frame from the camera and put it |
| 70 | + # in the source mat. If there is an error notify the output. |
| 71 | + if cvSink.grabFrame(mat) == 0: |
| 72 | + # Send the output frame the error |
| 73 | + outputStream.notifyError(cvSink.getError()) |
| 74 | + |
| 75 | + # Skip the rest of the current iteration |
| 76 | + continue |
| 77 | + |
| 78 | + cv2.cvtColor(mat, cv2.COLOR_RGB2GRAY, dst=grayMat) |
| 79 | + |
| 80 | + detections = detector.detect(grayMat) |
| 81 | + |
| 82 | + # have not seen any tags yet |
| 83 | + tags.clear() |
| 84 | + |
| 85 | + for detection in detections: |
| 86 | + # remember we saw this tag |
| 87 | + tags.append(detection.getId()) |
| 88 | + |
| 89 | + # draw lines around the tag |
| 90 | + for i in range(4): |
| 91 | + j = (i + 1) % 4 |
| 92 | + point1 = ( |
| 93 | + int(detection.getCorner(i).x), |
| 94 | + int(detection.getCorner(i).y), |
| 95 | + ) |
| 96 | + point2 = ( |
| 97 | + int(detection.getCorner(j).x), |
| 98 | + int(detection.getCorner(j).y), |
| 99 | + ) |
| 100 | + mat = cv2.line(mat, point1, point2, outlineColor, 2) |
| 101 | + |
| 102 | + # mark the center of the tag |
| 103 | + cx = int(detection.getCenter().x) |
| 104 | + cy = int(detection.getCenter().y) |
| 105 | + ll = 10 |
| 106 | + mat = cv2.line( |
| 107 | + mat, |
| 108 | + (cx - ll, cy), |
| 109 | + (cx + ll, cy), |
| 110 | + crossColor, |
| 111 | + 2, |
| 112 | + ) |
| 113 | + mat = cv2.line( |
| 114 | + mat, |
| 115 | + (cx, cy - ll), |
| 116 | + (cx, cy + ll), |
| 117 | + crossColor, |
| 118 | + 2, |
| 119 | + ) |
| 120 | + |
| 121 | + # identify the tag |
| 122 | + mat = cv2.putText( |
| 123 | + mat, |
| 124 | + str(detection.getId()), |
| 125 | + (cx + ll, cy), |
| 126 | + cv2.FONT_HERSHEY_SIMPLEX, |
| 127 | + 1, |
| 128 | + crossColor, |
| 129 | + 3, |
| 130 | + ) |
| 131 | + |
| 132 | + # determine pose |
| 133 | + pose = estimator.estimate(detection) |
| 134 | + |
| 135 | + # put pose into dashboard |
| 136 | + rot = pose.rotation() |
| 137 | + tagsTable.getEntry(f"pose_{detection.getId()}").setDoubleArray( |
| 138 | + [pose.X(), pose.Y(), pose.Z(), rot.X(), rot.Y(), rot.Z()] |
| 139 | + ) |
| 140 | + |
| 141 | + # put list of tags onto dashboard |
| 142 | + pubTags.set(tags) |
| 143 | + |
| 144 | + # Give output stream a new image to display |
| 145 | + outputStream.putFrame(mat) |
| 146 | + finally: |
| 147 | + pubTags.close() |
| 148 | + detector.close() |
136 | 149 |
|
137 | 150 | # The camera code will be killed when the robot.py program exits. If you wish to perform cleanup, |
138 | 151 | # you should register an atexit handler. The child process will NOT be launched when running the robot code in |
|
0 commit comments