Refactor Detection
This commit is contained in:
parent
3ed9e95ee9
commit
bcf840cb94
|
@ -8,9 +8,11 @@ buildscript {
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
apply plugin: 'maven-publish'
|
||||
apply plugin: 'com.android.library'
|
||||
|
||||
group = 'com.github.tearabite'
|
||||
|
||||
android {
|
||||
namespace = 'com.tearabite.ftctearabits'
|
||||
compileSdkVersion 29
|
||||
|
|
|
@ -1,4 +0,0 @@
|
|||
package com.tearabite.ftctearabits;
|
||||
|
||||
public enum Alliance { Blue, Red }
|
||||
|
|
@ -0,0 +1,4 @@
|
|||
package com.tearabite.ftctearabits.common;
|
||||
|
||||
public enum Alliance { Blue, Red }
|
||||
|
|
@ -0,0 +1,19 @@
|
|||
package com.tearabite.ftctearabits.graphics;
|
||||
|
||||
import android.graphics.Color;
|
||||
import android.graphics.Paint;
|
||||
|
||||
public class LinePaint extends Paint
|
||||
{
|
||||
public LinePaint(int color)
|
||||
{
|
||||
setColor(color);
|
||||
setAntiAlias(true);
|
||||
setStrokeCap(Paint.Cap.ROUND);
|
||||
}
|
||||
|
||||
public static LinePaint RED = new LinePaint(Color.RED);
|
||||
public static LinePaint BLUE = new LinePaint(Color.BLUE);
|
||||
public static LinePaint BLACK = new LinePaint(Color.BLACK);
|
||||
public static LinePaint WHITE = new LinePaint(Color.WHITE);
|
||||
}
|
|
@ -1,9 +1,10 @@
|
|||
package com.tearabite.ftctearabits.vision;
|
||||
|
||||
import static com.tearabite.ftctearabits.vision.Colors.FTC_BLUE_RANGE;
|
||||
import static com.tearabite.ftctearabits.vision.Colors.FTC_RED_RANGE_1;
|
||||
import static com.tearabite.ftctearabits.vision.Colors.FTC_RED_RANGE_2;
|
||||
import static com.tearabite.ftctearabits.vision.Colors.WHITE;
|
||||
import static com.tearabite.ftctearabits.graphics.LinePaint.WHITE;
|
||||
import static com.tearabite.ftctearabits.vision.Detection.PropertyScale.Pixels;
|
||||
import static com.tearabite.ftctearabits.vision.FTCColors.FTC_BLUE_RANGE;
|
||||
import static com.tearabite.ftctearabits.vision.FTCColors.FTC_RED_RANGE_1;
|
||||
import static com.tearabite.ftctearabits.vision.FTCColors.FTC_RED_RANGE_2;
|
||||
import static com.tearabite.ftctearabits.vision.OpenCVUtil.getLargestContour;
|
||||
|
||||
import android.graphics.Canvas;
|
||||
|
@ -29,12 +30,13 @@ public class BasicColorDetectionVisionProcessor implements VisionProcessor {
|
|||
public static final Point ANCHOR = new Point((STRUCTURING_ELEMENT.cols() / 2f), STRUCTURING_ELEMENT.rows() / 2f);
|
||||
|
||||
private final Mat blurred = new Mat();
|
||||
@Getter @Setter private ScalarRange[] colorRanges;
|
||||
@Getter private Detection detection;
|
||||
private final Mat hsv = new Mat();
|
||||
private final Mat mask = new Mat();
|
||||
private final Mat tmpMask = new Mat();
|
||||
|
||||
@Getter @Setter private ScalarRange[] colorRanges;
|
||||
@Getter private Detection detection;
|
||||
|
||||
|
||||
public BasicColorDetectionVisionProcessor(ScalarRange... colorRanges) {
|
||||
|
||||
|
@ -51,7 +53,7 @@ public class BasicColorDetectionVisionProcessor implements VisionProcessor {
|
|||
|
||||
@Override
|
||||
public void init(int width, int height, CameraCalibration calibration) {
|
||||
this.detection = new Detection(new Size(width, height), 0, 0);
|
||||
this.detection = Detection.builder().frameSize(new Size(width, height)).build();
|
||||
}
|
||||
|
||||
@Override
|
||||
|
@ -81,24 +83,24 @@ public class BasicColorDetectionVisionProcessor implements VisionProcessor {
|
|||
@Override
|
||||
public void onDrawFrame(Canvas canvas, int onscreenWidth, int onscreenHeight, float scaleBmpPxToCanvasPx, float scaleCanvasDensity, Object userContext) {
|
||||
if (detection != null && detection.isValid()) {
|
||||
Point center = detection.getCenterPx();
|
||||
Point center = detection.getCenter();
|
||||
canvas.drawCircle((float) center.x, (float) center.y, 10, WHITE);
|
||||
}
|
||||
}
|
||||
|
||||
public double getIgnoreSmallerThan() {
|
||||
return this.detection.getIgnoreSmallerThan();
|
||||
public double getMinimumAreaThreshold() {
|
||||
return this.detection.getMinimumAreaThreshold();
|
||||
}
|
||||
|
||||
public void setIgnoreSmallerThan(double ignoreSmallerThan) {
|
||||
this.detection.setIgnoreSmallerThan(ignoreSmallerThan);
|
||||
public void setMinimumAreaThreshold(double ignoreSmallerThan) {
|
||||
this.detection.setMinimumAreaThreshold(ignoreSmallerThan);
|
||||
}
|
||||
|
||||
public double getIgnoreLargerThan() {
|
||||
return this.detection.getIgnoreLargerThan();
|
||||
public double getMaximumAreaThreshold() {
|
||||
return this.detection.getMaximumAreaThreshold();
|
||||
}
|
||||
|
||||
public void setIgnoreLargerThan(double ignoreLargerThan) {
|
||||
this.detection.setIgnoreLargerThan(ignoreLargerThan);
|
||||
public void setMaximumAreaThreshold(double ignoreLargerThan) {
|
||||
this.detection.setMaximumAreaThreshold(ignoreLargerThan);
|
||||
}
|
||||
}
|
|
@ -1,151 +1,134 @@
|
|||
package com.tearabite.ftctearabits.vision;
|
||||
|
||||
import static com.tearabite.ftctearabits.vision.Constants.GREEN;
|
||||
import static com.tearabite.ftctearabits.vision.OpenCVUtil.drawConvexHull;
|
||||
import static com.tearabite.ftctearabits.vision.OpenCVUtil.drawPoint;
|
||||
import static com.tearabite.ftctearabits.vision.OpenCVUtil.fillConvexHull;
|
||||
import static com.tearabite.ftctearabits.vision.OpenCVUtil.getBottomLeftOfContour;
|
||||
import static com.tearabite.ftctearabits.vision.OpenCVUtil.getBottomRightOfContour;
|
||||
import static com.tearabite.ftctearabits.vision.OpenCVUtil.getCenterOfContour;
|
||||
|
||||
import android.graphics.drawable.Icon;
|
||||
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.core.MatOfPoint;
|
||||
import org.opencv.core.Point;
|
||||
import org.opencv.core.Scalar;
|
||||
import org.opencv.core.Size;
|
||||
import org.opencv.imgproc.Imgproc;
|
||||
|
||||
// Class for a Detection
|
||||
import lombok.AllArgsConstructor;
|
||||
import lombok.Builder;
|
||||
import lombok.Getter;
|
||||
import lombok.NoArgsConstructor;
|
||||
import lombok.Setter;
|
||||
|
||||
@NoArgsConstructor()
|
||||
@AllArgsConstructor
|
||||
@Builder
|
||||
public class Detection {
|
||||
public static final Point INVALID_POINT = new Point(Double.MIN_VALUE, Double.MIN_VALUE);
|
||||
public static final double INVALID_AREA = -1;
|
||||
public static final Detection INVALID_DETECTION = new Detection(new Size(0, 0), 0);
|
||||
|
||||
private double minAreaPx;
|
||||
private final double maxAreaPx;
|
||||
private final Size maxSizePx;
|
||||
private double areaPx = INVALID_AREA;
|
||||
private Point centerPx = INVALID_POINT;
|
||||
private Point bottomLeftPx = INVALID_POINT;
|
||||
private Point bottomRightPx = INVALID_POINT;
|
||||
private MatOfPoint contour;
|
||||
@Getter @Setter private MatOfPoint contour;
|
||||
@Getter @Setter private Size frameSize;
|
||||
@Getter @Setter private double maxAreaThreshold;
|
||||
@Getter @Setter private double minAreaThreshold;
|
||||
|
||||
// Constructor
|
||||
public Detection(Size frameSize, double minAreaFactor) {
|
||||
this.maxSizePx = frameSize;
|
||||
this.minAreaPx = frameSize.area() * minAreaFactor;
|
||||
this.maxAreaPx = frameSize.area();
|
||||
}
|
||||
|
||||
public Detection(Size frameSize, double minAreaFactor, double maxAreaFactor) {
|
||||
this.maxSizePx = frameSize;
|
||||
this.minAreaPx = frameSize.area() * minAreaFactor;
|
||||
this.maxAreaPx = frameSize.area() * maxAreaFactor;
|
||||
}
|
||||
|
||||
public void setMinArea(double minAreaFactor) {
|
||||
this.minAreaPx = maxSizePx.area() * minAreaFactor;
|
||||
}
|
||||
|
||||
public void setMaxArea(double maxAreaFactor) {
|
||||
this.minAreaPx = maxSizePx.area() * maxAreaFactor;
|
||||
}
|
||||
|
||||
// Draw a convex hull around the current detection on the given image
|
||||
public void draw(Mat img, Scalar color) {
|
||||
if (isValid()) {
|
||||
drawConvexHull(img, contour, color);
|
||||
drawPoint(img, centerPx, GREEN);
|
||||
}
|
||||
}
|
||||
|
||||
// Draw a convex hull around the current detection on the given image
|
||||
public void fill(Mat img, Scalar color) {
|
||||
if (isValid()) {
|
||||
fillConvexHull(img, contour, color);
|
||||
drawPoint(img, centerPx, GREEN);
|
||||
}
|
||||
}
|
||||
|
||||
// Check if the current Detection is valid
|
||||
public boolean isValid() {
|
||||
return (this.contour != null) && (this.areaPx != INVALID_AREA);
|
||||
double area = getArea();
|
||||
return contour != null
|
||||
&& area > minAreaThreshold
|
||||
&& area < maxAreaThreshold;
|
||||
}
|
||||
|
||||
// Get the current contour
|
||||
public MatOfPoint getContour() {
|
||||
return contour;
|
||||
}
|
||||
|
||||
// Set the values of the current contour
|
||||
public void setContour(MatOfPoint contour) {
|
||||
this.contour = contour;
|
||||
|
||||
double area;
|
||||
if (contour != null && (area = Imgproc.contourArea(contour)) > minAreaPx && area < maxAreaPx) {
|
||||
this.areaPx = area;
|
||||
this.centerPx = getCenterOfContour(contour);
|
||||
this.bottomLeftPx = getBottomLeftOfContour(contour);
|
||||
this.bottomRightPx = getBottomRightOfContour(contour);
|
||||
} else {
|
||||
this.areaPx = INVALID_AREA;
|
||||
this.centerPx = INVALID_POINT;
|
||||
this.bottomLeftPx = INVALID_POINT;
|
||||
this.bottomRightPx = INVALID_POINT;
|
||||
}
|
||||
}
|
||||
|
||||
// Returns the center of the Detection, normalized so that the width and height of the frame is from [-50,50]
|
||||
public Point getCenter() {
|
||||
if (!isValid()) {
|
||||
return INVALID_POINT;
|
||||
}
|
||||
|
||||
double normalizedX = ((centerPx.x / maxSizePx.width) * 100) - 50;
|
||||
double normalizedY = ((centerPx.y / maxSizePx.height) * -100) + 50;
|
||||
|
||||
return new Point(normalizedX, normalizedY);
|
||||
}
|
||||
|
||||
// Get the center point in pixels
|
||||
public Point getCenterPx() {
|
||||
return centerPx;
|
||||
}
|
||||
|
||||
// Get the area of the Detection, normalized so that the area of the frame is 100
|
||||
public double getArea() {
|
||||
public double getArea(PropertyScale scale) {
|
||||
if (!isValid()) {
|
||||
return INVALID_AREA;
|
||||
}
|
||||
|
||||
return (areaPx / (maxSizePx.width * maxSizePx.height)) * 100;
|
||||
double areaPx = Imgproc.contourArea(contour);
|
||||
if (scale == PropertyScale.Pixels) {
|
||||
return areaPx;
|
||||
}
|
||||
|
||||
// Get the leftmost bottom corner of the detection
|
||||
public Point getBottomLeftCornerPx() {
|
||||
return bottomLeftPx;
|
||||
return (areaPx / (frameSize.width * frameSize.height)) * 100;
|
||||
}
|
||||
|
||||
// Get the rightmost bottom corner of the detection
|
||||
public Point getBottomRightCornerPx() {
|
||||
return bottomRightPx;
|
||||
public double getArea() {
|
||||
return getArea(PropertyScale.Pixels);
|
||||
}
|
||||
|
||||
public void setIgnoreSmallerThan(double ignoreSmallerThan) {
|
||||
this.minAreaPx = maxSizePx.area() * ignoreSmallerThan;
|
||||
public Point getCenter(PropertyScale scale) {
|
||||
if (!isValid()) {
|
||||
return INVALID_POINT;
|
||||
}
|
||||
|
||||
public void setIgnoreLargerThan(double ignoreLargerThan) {
|
||||
this.minAreaPx = maxSizePx.area() * ignoreLargerThan;
|
||||
Point centerPx = getCenterOfContour(this.contour);
|
||||
if (scale == PropertyScale.Pixels) {
|
||||
return centerPx;
|
||||
}
|
||||
|
||||
public double getIgnoreSmallerThan() {
|
||||
return this.minAreaPx / this.maxSizePx.area();
|
||||
return pixelPointToPercentageOfFrame(centerPx);
|
||||
}
|
||||
|
||||
public double getIgnoreLargerThan() {
|
||||
return this.maxAreaPx / this.maxSizePx.area();
|
||||
public Point getCenter() {
|
||||
return getCenter(PropertyScale.Pixels);
|
||||
}
|
||||
|
||||
public void setMaximumAreaThreshold(double ignoreLargerThan, PropertyScale scale) {
|
||||
switch (scale) {
|
||||
case Pixels:
|
||||
this.maxAreaThreshold = ignoreLargerThan;
|
||||
break;
|
||||
case Percent:
|
||||
this.maxAreaThreshold = frameSize.area() * ignoreLargerThan;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
public void setMaximumAreaThreshold(double threshold) {
|
||||
setMaximumAreaThreshold(threshold, PropertyScale.Pixels);
|
||||
}
|
||||
|
||||
public void setMinimumAreaThreshold(double threshold, PropertyScale scale) {
|
||||
switch (scale) {
|
||||
case Pixels:
|
||||
this.minAreaThreshold = threshold;
|
||||
break;
|
||||
case Percent:
|
||||
this.minAreaThreshold = frameSize.area() * threshold;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
public void setMinimumAreaThreshold(double threshold) {
|
||||
setMinimumAreaThreshold(threshold, PropertyScale.Pixels);
|
||||
}
|
||||
|
||||
public double getMaximumAreaThreshold(PropertyScale scale) {
|
||||
switch (scale) {
|
||||
default:
|
||||
case Pixels:
|
||||
return this.maxAreaThreshold;
|
||||
case Percent:
|
||||
return this.maxAreaThreshold / this.frameSize.area();
|
||||
}
|
||||
}
|
||||
|
||||
public double getMaximumAreaThreshold() {
|
||||
return getMaximumAreaThreshold(PropertyScale.Pixels);
|
||||
}
|
||||
|
||||
public double getMinimumAreaThreshold(PropertyScale scale) {
|
||||
switch (scale) {
|
||||
default:
|
||||
case Pixels:
|
||||
return this.minAreaThreshold;
|
||||
case Percent:
|
||||
return this.minAreaThreshold / this.frameSize.area();
|
||||
}
|
||||
}
|
||||
|
||||
public double getMinimumAreaThreshold() {
|
||||
return getMinimumAreaThreshold(PropertyScale.Pixels);
|
||||
}
|
||||
|
||||
public enum PropertyScale { Pixels, Percent }
|
||||
|
||||
private Point pixelPointToPercentageOfFrame(Point pixelPoint) {
|
||||
double normalizedX = ((pixelPoint.x / frameSize.width) * 100) - 50;
|
||||
double normalizedY = ((pixelPoint.y / frameSize.height) * -100) + 50;
|
||||
return new Point(normalizedX, normalizedY);
|
||||
}
|
||||
}
|
|
@ -3,7 +3,7 @@ package com.tearabite.ftctearabits.vision;
|
|||
import android.graphics.Color;
|
||||
|
||||
import org.opencv.core.Scalar;
|
||||
public class Colors {
|
||||
public class FTCColors {
|
||||
public static Scalar FTC_RED_LOWER = new Scalar(165, 80, 80);
|
||||
public static Scalar FTC_RED_UPPER = new Scalar(15, 255, 255);
|
||||
public static ScalarRange FTC_RED_RANGE_1 = new ScalarRange(new Scalar(180, FTC_RED_UPPER.val[1], FTC_RED_UPPER.val[2]), FTC_RED_LOWER);
|
||||
|
@ -13,9 +13,4 @@ public class Colors {
|
|||
public static ScalarRange FTC_BLUE_RANGE = new ScalarRange(FTC_BLUE_UPPER, FTC_BLUE_LOWER);
|
||||
public static Scalar FTC_WHITE_LOWER = new Scalar(0, 0, 40);
|
||||
public static Scalar FTC_WHITE_UPPER = new Scalar(180, 30, 255);
|
||||
|
||||
public static OpenCVUtil.LinePaint RED = new OpenCVUtil.LinePaint(Color.RED);
|
||||
public static OpenCVUtil.LinePaint BLUE = new OpenCVUtil.LinePaint(Color.BLUE);
|
||||
public static OpenCVUtil.LinePaint BLACK = new OpenCVUtil.LinePaint(Color.BLACK);
|
||||
public static OpenCVUtil.LinePaint WHITE = new OpenCVUtil.LinePaint(Color.WHITE);
|
||||
}
|
|
@ -1,7 +1,5 @@
|
|||
package com.tearabite.ftctearabits.vision;
|
||||
|
||||
import android.graphics.Paint;
|
||||
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.core.MatOfInt;
|
||||
import org.opencv.core.MatOfPoint;
|
||||
|
@ -89,14 +87,4 @@ public class OpenCVUtil {
|
|||
Collections.sort(contours, (a, b) -> (int) Imgproc.contourArea(b) - (int) Imgproc.contourArea(a));
|
||||
return contours.subList(0, Math.min(numContours, contours.size()));
|
||||
}
|
||||
|
||||
public static class LinePaint extends Paint
|
||||
{
|
||||
public LinePaint(int color)
|
||||
{
|
||||
setColor(color);
|
||||
setAntiAlias(true);
|
||||
setStrokeCap(Paint.Cap.ROUND);
|
||||
}
|
||||
}
|
||||
}
|
Loading…
Reference in New Issue