blob: 0caf1f17e65f2848d66570f30ef9a1f581c59575 [file] [log] [blame]
jerrym6ebe6452013-02-18 03:00:31 +00001package org.frc971;
2
3import java.util.ArrayList;
4
5import com.googlecode.javacv.cpp.opencv_core;
6import com.googlecode.javacv.cpp.opencv_core.CvSize;
7import com.googlecode.javacv.cpp.opencv_core.IplImage;
8import com.googlecode.javacv.cpp.opencv_imgproc;
9import com.googlecode.javacv.cpp.opencv_imgproc.IplConvKernel;
10
11import edu.wpi.first.wpijavacv.DaisyExtensions;
12import edu.wpi.first.wpijavacv.WPIBinaryImage;
13import edu.wpi.first.wpijavacv.WPIColor;
14import edu.wpi.first.wpijavacv.WPIColorImage;
15import edu.wpi.first.wpijavacv.WPIContour;
16import edu.wpi.first.wpijavacv.WPIImage;
17import edu.wpi.first.wpijavacv.WPIPoint;
18import edu.wpi.first.wpijavacv.WPIPolygon;
19
20/**
21 * Vision target recognizer for FRC 2013.
22 *
23 * @author jerry
24 */
25public class Recognizer2013 implements Recognizer {
26
jerrymaa7a63b2013-02-18 06:31:22 +000027 // --- Constants that need to be tuned.
jerrymcd2c3322013-02-18 08:49:01 +000028 static final double kRoughlyHorizontalSlope = Math.tan(Math.toRadians(30));
29 static final double kRoughlyVerticalSlope = Math.tan(Math.toRadians(90 - 30));
jerrymcd2c3322013-02-18 08:49:01 +000030 static final int kHoleClosingIterations = 2;
31 static final double kPolygonPercentFit = 12;
jerrymaa7a63b2013-02-18 06:31:22 +000032
33 static final int kMinWidthAt320 = 35; // for high goal and middle goals
34
35 // These aspect ratios include the outside edges of the vision target tape.
36 static final double kHighGoalAspect = (21 + 8.0) / (54 + 8);
37 static final double kMiddleGoalAspect = (24 + 8.0) / (54 + 8);
38 static final double kMinAspect = kHighGoalAspect * 0.6;
39 static final double kMaxAspect = kMiddleGoalAspect * 1.4;
jerrym6ebe6452013-02-18 03:00:31 +000040
41 static final double kShooterOffsetDeg = 0;
42 static final double kHorizontalFOVDeg = 47.0;
43 static final double kVerticalFOVDeg = 480.0 / 640.0 * kHorizontalFOVDeg;
44
jerrymaa7a63b2013-02-18 06:31:22 +000045 // --- Colors for drawing indicators on the image.
jerrym6ebe6452013-02-18 03:00:31 +000046 private static final WPIColor reject1Color = WPIColor.GRAY;
47 private static final WPIColor reject2Color = WPIColor.YELLOW;
48 private static final WPIColor candidateColor = WPIColor.BLUE;
49 private static final WPIColor targetColor = new WPIColor(255, 0, 0);
50
jerrymcd2469c2013-02-18 20:15:28 +000051 private int min1Hue, max1Hue, min1Sat, min1Val;
52
jerrym6ebe6452013-02-18 03:00:31 +000053 // Show intermediate images for parameter tuning.
54 private final DebugCanvas thresholdedCanvas = new DebugCanvas("thresholded");
55 private final DebugCanvas morphedCanvas = new DebugCanvas("morphed");
56
jerrymaa7a63b2013-02-18 06:31:22 +000057 // Data to reuse for each frame.
jerrym6ebe6452013-02-18 03:00:31 +000058 private final DaisyExtensions daisyExtensions = new DaisyExtensions();
59 private final IplConvKernel morphKernel = IplConvKernel.create(3, 3, 1, 1,
jerrymdda60132013-02-18 09:25:03 +000060 opencv_imgproc.CV_SHAPE_RECT, null);
jerrym6ebe6452013-02-18 03:00:31 +000061 private final ArrayList<WPIPolygon> polygons = new ArrayList<WPIPolygon>();
jerrymaa7a63b2013-02-18 06:31:22 +000062
63 // Frame-size-dependent data to reuse for each frame.
64 private CvSize size = null;
jerrym6ebe6452013-02-18 03:00:31 +000065 private WPIColorImage rawImage;
66 private IplImage bin;
67 private IplImage hsv;
68 private IplImage hue;
69 private IplImage sat;
70 private IplImage val;
jerrymaa7a63b2013-02-18 06:31:22 +000071 private int minWidth;
jerrym6ebe6452013-02-18 03:00:31 +000072 private WPIPoint linePt1, linePt2; // crosshair endpoints
73
74 public Recognizer2013() {
jerrymdda60132013-02-18 09:25:03 +000075 setHSVRange(70, 106, 137, 27);
jerrym6ebe6452013-02-18 03:00:31 +000076 }
77
78 @Override
jerrymcd2c3322013-02-18 08:49:01 +000079 public void setHSVRange(int minHue, int maxHue, int minSat, int minVal) {
jerrymdda60132013-02-18 09:25:03 +000080 min1Hue = minHue - 1; // - 1 because cvThreshold() does > instead of >=
81 max1Hue = maxHue + 1;
82 min1Sat = minSat - 1;
83 min1Val = minVal - 1;
jerrymcd2c3322013-02-18 08:49:01 +000084 }
85 @Override
86 public int getHueMin() { return min1Hue + 1; }
87 @Override
88 public int getHueMax() { return max1Hue - 1; }
89 @Override
jerrymcd2469c2013-02-18 20:15:28 +000090 public int getSatMin() { return min1Sat + 1; }
jerrymcd2c3322013-02-18 08:49:01 +000091 @Override
jerrymcd2469c2013-02-18 20:15:28 +000092 public int getValMin() { return min1Val + 1; }
jerrymcd2c3322013-02-18 08:49:01 +000093
94 @Override
jerrymf96c32c2013-02-18 19:30:45 +000095 public void showIntermediateStages(boolean enable) {
96 thresholdedCanvas.show = enable;
97 morphedCanvas.show = enable;
98 }
99
100 @Override
jerrym6ebe6452013-02-18 03:00:31 +0000101 public WPIImage processImage(WPIColorImage cameraImage) {
jerrymdda60132013-02-18 09:25:03 +0000102 // (Re)allocate the intermediate images if the input is a different
103 // size than the previous image.
jerrym6ebe6452013-02-18 03:00:31 +0000104 if (size == null || size.width() != cameraImage.getWidth()
jerrymdda60132013-02-18 09:25:03 +0000105 || size.height() != cameraImage.getHeight()) {
jerrym6ebe6452013-02-18 03:00:31 +0000106 size = opencv_core.cvSize(cameraImage.getWidth(),
jerrymdda60132013-02-18 09:25:03 +0000107 cameraImage.getHeight());
jerrym6ebe6452013-02-18 03:00:31 +0000108 rawImage = DaisyExtensions.makeWPIColorImage(
jerrymdda60132013-02-18 09:25:03 +0000109 DaisyExtensions.getIplImage(cameraImage));
jerrym6ebe6452013-02-18 03:00:31 +0000110 bin = IplImage.create(size, 8, 1);
111 hsv = IplImage.create(size, 8, 3);
112 hue = IplImage.create(size, 8, 1);
113 sat = IplImage.create(size, 8, 1);
114 val = IplImage.create(size, 8, 1);
jerrymaa7a63b2013-02-18 06:31:22 +0000115 minWidth = (kMinWidthAt320 * cameraImage.getWidth() + 319) / 320;
jerrym6ebe6452013-02-18 03:00:31 +0000116
117 int horizontalOffsetPixels = (int)Math.round(
jerrymdda60132013-02-18 09:25:03 +0000118 kShooterOffsetDeg * size.width() / kHorizontalFOVDeg);
jerrym6ebe6452013-02-18 03:00:31 +0000119 int x = size.width() / 2 + horizontalOffsetPixels;
120 linePt1 = new WPIPoint(x, size.height() - 1);
121 linePt2 = new WPIPoint(x, 0);
122 } else {
jerrymaa7a63b2013-02-18 06:31:22 +0000123 // Copy the camera image so it's safe to draw on.
jerrym6ebe6452013-02-18 03:00:31 +0000124 opencv_core.cvCopy(DaisyExtensions.getIplImage(cameraImage),
jerrymdda60132013-02-18 09:25:03 +0000125 DaisyExtensions.getIplImage(rawImage));
jerrym6ebe6452013-02-18 03:00:31 +0000126 }
127
128 IplImage input = DaisyExtensions.getIplImage(rawImage);
129
130 // Threshold the pixels in HSV color space.
131 // TODO(jerry): Do this in one pass of a pixel-processing loop.
jerrymaa7a63b2013-02-18 06:31:22 +0000132 opencv_imgproc.cvCvtColor(input, hsv, opencv_imgproc.CV_BGR2HSV_FULL);
jerrym6ebe6452013-02-18 03:00:31 +0000133 opencv_core.cvSplit(hsv, hue, sat, val, null);
134
135 // NOTE: Since red is at the end of the cyclic color space, you can OR
136 // a threshold and an inverted threshold to match red pixels.
jerrymcd2c3322013-02-18 08:49:01 +0000137 opencv_imgproc.cvThreshold(hue, bin, min1Hue, 255, opencv_imgproc.CV_THRESH_BINARY);
138 opencv_imgproc.cvThreshold(hue, hue, max1Hue, 255, opencv_imgproc.CV_THRESH_BINARY_INV);
139 opencv_imgproc.cvThreshold(sat, sat, min1Sat, 255, opencv_imgproc.CV_THRESH_BINARY);
140 opencv_imgproc.cvThreshold(val, val, min1Val, 255, opencv_imgproc.CV_THRESH_BINARY);
jerrym6ebe6452013-02-18 03:00:31 +0000141
142 // Combine the results to obtain a binary image which is mostly the
143 // interesting pixels.
144 opencv_core.cvAnd(hue, bin, bin, null);
145 opencv_core.cvAnd(bin, sat, bin, null);
146 opencv_core.cvAnd(bin, val, bin, null);
147
148 thresholdedCanvas.showImage(bin);
149
150 // Fill in gaps using binary morphology.
151 opencv_imgproc.cvMorphologyEx(bin, bin, null, morphKernel,
jerrymdda60132013-02-18 09:25:03 +0000152 opencv_imgproc.CV_MOP_CLOSE, kHoleClosingIterations);
jerrym6ebe6452013-02-18 03:00:31 +0000153
154 morphedCanvas.showImage(bin);
155
156 // Find contours.
157 WPIBinaryImage binWpi = DaisyExtensions.makeWPIBinaryImage(bin);
jerrymaa7a63b2013-02-18 06:31:22 +0000158 WPIContour[] contours = daisyExtensions.findConvexContours(binWpi);
jerrym6ebe6452013-02-18 03:00:31 +0000159
jerrymaa7a63b2013-02-18 06:31:22 +0000160 // Simplify the contours to polygons and filter by size and aspect ratio.
161 //
162 // TODO(jerry): Also look for the two vertical stripe vision targets.
163 // They'll greatly increase the precision of measuring the distance. If
164 // both stripes are visible, they'll increase the accuracy for
165 // identifying the high goal.
jerrym6ebe6452013-02-18 03:00:31 +0000166 polygons.clear();
167 for (WPIContour c : contours) {
jerrymaa7a63b2013-02-18 06:31:22 +0000168 if (c.getWidth() >= minWidth) {
jerrymdda60132013-02-18 09:25:03 +0000169 double ratio = ((double) c.getHeight()) / c.getWidth();
170 if (ratio >= kMinAspect && ratio <= kMaxAspect) {
171 polygons.add(c.approxPolygon(kPolygonPercentFit));
172 // System.out.println(" Accepted aspect ratio " + ratio);
173 } else {
174 // System.out.println(" Rejected aspect ratio " + ratio);
175 }
jerrym6ebe6452013-02-18 03:00:31 +0000176 }
177 }
178
jerrymaa7a63b2013-02-18 06:31:22 +0000179 // Pick the target with the highest center-point that matches yet more
180 // filter criteria.
jerrym6ebe6452013-02-18 03:00:31 +0000181 WPIPolygon bestTarget = null;
182 int highestY = Integer.MAX_VALUE;
183
184 for (WPIPolygon p : polygons) {
jerrymaa7a63b2013-02-18 06:31:22 +0000185 // TODO(jerry): Replace boolean filters with a scoring function?
jerrym6ebe6452013-02-18 03:00:31 +0000186 if (p.isConvex() && p.getNumVertices() == 4) { // quadrilateral
187 WPIPoint[] points = p.getPoints();
jerrymaa7a63b2013-02-18 06:31:22 +0000188 // Filter for polygons with 2 ~horizontal and 2 ~vertical sides.
jerrym6ebe6452013-02-18 03:00:31 +0000189 int numRoughlyHorizontal = 0;
190 int numRoughlyVertical = 0;
191 for (int i = 0; i < 4; ++i) {
192 double dy = points[i].getY() - points[(i + 1) % 4].getY();
193 double dx = points[i].getX() - points[(i + 1) % 4].getX();
194 double slope = Double.MAX_VALUE;
195 if (dx != 0) {
196 slope = Math.abs(dy / dx);
197 }
198
199 if (slope < kRoughlyHorizontalSlope) {
200 ++numRoughlyHorizontal;
201 } else if (slope > kRoughlyVerticalSlope) {
202 ++numRoughlyVertical;
203 }
204 }
205
jerrymaa7a63b2013-02-18 06:31:22 +0000206 if (numRoughlyHorizontal >= 2 && numRoughlyVertical == 2) {
jerrym6ebe6452013-02-18 03:00:31 +0000207 rawImage.drawPolygon(p, candidateColor, 2);
208
209 int pCenterX = p.getX() + p.getWidth() / 2;
210 int pCenterY = p.getY() + p.getHeight() / 2;
211
212 rawImage.drawPoint(new WPIPoint(pCenterX, pCenterY),
jerrymdda60132013-02-18 09:25:03 +0000213 targetColor, 2);
jerrym6ebe6452013-02-18 03:00:31 +0000214 if (pCenterY < highestY) {
215 bestTarget = p;
216 highestY = pCenterY;
217 }
218 } else {
219 rawImage.drawPolygon(p, reject2Color, 1);
220 }
221 } else {
222 rawImage.drawPolygon(p, reject1Color, 1);
223 }
224 }
225
226 if (bestTarget != null) {
227 double w = bestTarget.getWidth();
228 double h = bestTarget.getHeight();
229 double x = bestTarget.getX() + w / 2;
230 double y = bestTarget.getY() + h / 2;
231
232 rawImage.drawPolygon(bestTarget, targetColor, 2);
233
234 System.out.println("Best target at (" + x + ", " + y + ") size "
jerrymdda60132013-02-18 09:25:03 +0000235 + w + " x " + h);
jerrym6ebe6452013-02-18 03:00:31 +0000236 } else {
237 System.out.println("No target found");
238 }
239
240 // Draw a crosshair
241 rawImage.drawLine(linePt1, linePt2, targetColor, 1);
242
243 daisyExtensions.releaseMemory();
244 //System.gc();
245
246 return rawImage;
247 }
248
249}