Use chessboard squares (vs interior corners); fix resolution selector bug (#139)

* Change chessboard size to be squares not interior corners

This reduces ambiguity

* Force users to select resolution

This forces the correct video mode index to be selected. Otherwise the 0th camera videomode index will be used, as it's zero-inited. This is undesirable.

* Make target model an enum

This will allow the UI to remember the currently selected target.
This commit is contained in:
Matt
2020-10-13 06:58:50 -07:00
committed by GitHub
parent 6e0a6b804e
commit 23f3c0e6e1
13 changed files with 146 additions and 194 deletions

View File

@@ -33,6 +33,7 @@ import org.photonvision.common.networking.NetworkManager;
import org.photonvision.common.util.TestUtils;
import org.photonvision.server.Server;
import org.photonvision.vision.camera.FileVisionSource;
import org.photonvision.vision.opencv.ContourGroupingMode;
import org.photonvision.vision.pipeline.CVPipelineSettings;
import org.photonvision.vision.pipeline.ReflectivePipelineSettings;
import org.photonvision.vision.processes.VisionModule;
@@ -93,7 +94,9 @@ public class Main {
var pipeline2019 = new ReflectivePipelineSettings();
pipeline2019.pipelineNickname = "CargoShip";
pipeline2019.targetModel = TargetModel.get2019Target();
pipeline2019.targetModel = TargetModel.k2019DualTarget;
pipeline2019.outputShowMultipleTargets = true;
pipeline2019.contourGroupingMode = ContourGroupingMode.Dual;
var psList2019 = new ArrayList<CVPipelineSettings>();
psList2019.add(pipeline2019);
@@ -107,7 +110,7 @@ public class Main {
var pipeline2020 = new ReflectivePipelineSettings();
pipeline2020.pipelineNickname = "OuterPort";
pipeline2020.targetModel = TargetModel.get2020Target();
pipeline2020.targetModel = TargetModel.k2020HighGoalOuter;
camConf2020.calibrations.add(TestUtils.get2020LifeCamCoeffs(true));
var psList2020 = new ArrayList<CVPipelineSettings>();

View File

@@ -17,15 +17,21 @@
package org.photonvision.vision.pipe.impl;
import java.util.Objects;
import org.apache.commons.lang3.tuple.Triple;
import org.opencv.calib3d.Calib3d;
import org.opencv.core.*;
import org.opencv.imgproc.Imgproc;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.Logger;
import org.photonvision.vision.pipe.CVPipe;
import org.photonvision.vision.pipeline.UICalibrationData;
public class FindBoardCornersPipe
extends CVPipe<Mat, Triple<Size, Mat, Mat>, FindBoardCornersPipe.FindCornersPipeParams> {
private static final Logger logger =
new Logger(FindBoardCornersPipe.class, LogGroup.VisionModule);
MatOfPoint3f objectPoints = new MatOfPoint3f();
Size imageSize;
@@ -38,25 +44,22 @@ public class FindBoardCornersPipe
private final Size zeroZone = new Size(-1, -1);
private final TermCriteria criteria = new TermCriteria(3, 30, 0.001);
private boolean objectPointsCreated = false;
@Override
public void setParams(FindCornersPipeParams params) {
super.setParams(params);
if (new Size(params.boardWidth, params.boardHeight).equals(patternSize)) return;
objectPointsCreated = false;
}
private FindCornersPipeParams lastParams = null;
public void createObjectPoints() {
if (objectPointsCreated) return; // TODO reinstantiate on settings change
if (this.lastParams != null && this.lastParams.equals(this.params)) return;
this.lastParams = this.params;
/*If using a chessboard, then the pattern size if the inner corners of the board. For example, the pattern size of a 9x9 chessboard would be 8x8
If using a dot board, then the pattern size width is the sum of the bottom 2 rows and the height is the left or right most column
For example, a 5x4 dot board would have a pattern size of 11x4
We subtract 1 for chessboard because the UI prompts users for the number of squares, not the
number of corners.
* */
this.patternSize = new Size(params.boardWidth, params.boardHeight);
this.patternSize =
params.type == UICalibrationData.BoardType.CHESSBOARD
? new Size(params.boardWidth - 1, params.boardHeight - 1)
: new Size(params.boardWidth, params.boardHeight);
// Chessboard and dot board have different 3D points to project as a dot board has alternating
// dots per column
@@ -81,9 +84,8 @@ public class FindBoardCornersPipe
}
}
} else {
// TOOD log
logger.error("Can't create pattern for unknown board type " + params.type);
}
objectPointsCreated = true;
}
/**
@@ -162,5 +164,21 @@ public class FindBoardCornersPipe
this.type = type;
this.gridSize = gridSize; // mm
}
@Override
public boolean equals(Object o) {
if (this == o) return true;
if (o == null || getClass() != o.getClass()) return false;
FindCornersPipeParams that = (FindCornersPipeParams) o;
return boardHeight == that.boardHeight
&& boardWidth == that.boardWidth
&& Double.compare(that.gridSize, gridSize) == 0
&& type == that.type;
}
@Override
public int hashCode() {
return Objects.hash(boardHeight, boardWidth, type, gridSize);
}
}
}

View File

@@ -21,8 +21,8 @@ import edu.wpi.first.wpilibj.util.Units;
import org.opencv.core.Size;
public class Calibration3dPipelineSettings extends AdvancedPipelineSettings {
public int boardHeight = 7;
public int boardWidth = 7;
public int boardHeight = 8;
public int boardWidth = 8;
public UICalibrationData.BoardType boardType = UICalibrationData.BoardType.CHESSBOARD;
public double gridSize = Units.inchesToMeters(1.0);

View File

@@ -34,7 +34,7 @@ public class ReflectivePipelineSettings extends AdvancedPipelineSettings {
// 3d settings
public boolean solvePNPEnabled = false;
public TargetModel targetModel = TargetModel.get2020Target();
public TargetModel targetModel = TargetModel.k2020HighGoalOuter;
// Corner detection settings
public CornerDetectionPipe.DetectionStrategy cornerDetectionStrategy =

View File

@@ -23,21 +23,71 @@ import com.fasterxml.jackson.annotation.JsonProperty;
import edu.wpi.first.wpilibj.util.Units;
import java.util.ArrayList;
import java.util.List;
import java.util.Objects;
import org.opencv.core.MatOfPoint3f;
import org.opencv.core.Point3;
import org.photonvision.vision.opencv.Releasable;
public class TargetModel implements Releasable {
public enum TargetModel implements Releasable {
k2020HighGoalOuter(
List.of(
new Point3(Units.inchesToMeters(-19.625), 0, 0),
new Point3(Units.inchesToMeters(-9.819867), Units.inchesToMeters(-17), 0),
new Point3(Units.inchesToMeters(9.819867), Units.inchesToMeters(-17), 0),
new Point3(Units.inchesToMeters(19.625), 0, 0)),
Units.inchesToMeters(12)),
k2020HighGoalInner(
List.of(
new Point3(Units.inchesToMeters(-19.625), 0, Units.inchesToMeters(2d * 12d + 5.25)),
new Point3(
Units.inchesToMeters(-9.819867),
Units.inchesToMeters(-17),
Units.inchesToMeters(2d * 12d + 5.25)),
new Point3(
Units.inchesToMeters(9.819867),
Units.inchesToMeters(-17),
Units.inchesToMeters(2d * 12d + 5.25)),
new Point3(Units.inchesToMeters(19.625), 0, Units.inchesToMeters(2d * 12d + 5.25))),
Units.inchesToMeters(12)),
k2019DualTarget(
List.of(
new Point3(Units.inchesToMeters(-5.936), Units.inchesToMeters(2.662), 0),
new Point3(Units.inchesToMeters(-7.313), Units.inchesToMeters(-2.662), 0),
new Point3(Units.inchesToMeters(7.313), Units.inchesToMeters(-2.662), 0),
new Point3(Units.inchesToMeters(5.936), Units.inchesToMeters(2.662), 0)),
0.1),
kCircularPowerCell7in(
List.of(
new Point3(
-Units.inchesToMeters(7) / 2,
-Units.inchesToMeters(7) / 2,
-Units.inchesToMeters(7) / 2),
new Point3(
-Units.inchesToMeters(7) / 2,
Units.inchesToMeters(7) / 2,
-Units.inchesToMeters(7) / 2),
new Point3(
Units.inchesToMeters(7) / 2,
Units.inchesToMeters(7) / 2,
-Units.inchesToMeters(7) / 2),
new Point3(
Units.inchesToMeters(7) / 2,
-Units.inchesToMeters(7) / 2,
-Units.inchesToMeters(7) / 2)),
0);
@JsonIgnore private final MatOfPoint3f realWorldTargetCoordinates;
@JsonIgnore private final MatOfPoint3f visualizationBoxBottom = new MatOfPoint3f();
@JsonIgnore private final MatOfPoint3f visualizationBoxTop = new MatOfPoint3f();
@JsonIgnore private MatOfPoint3f realWorldTargetCoordinates;
@JsonIgnore private MatOfPoint3f visualizationBoxBottom = new MatOfPoint3f();
@JsonIgnore private MatOfPoint3f visualizationBoxTop = new MatOfPoint3f();
public final List<Point3> realWorldCoordinatesArray;
public final double boxHeight;
@JsonProperty("realWorldCoordinatesArray")
private List<Point3> realWorldCoordinatesArray;
public TargetModel(MatOfPoint3f realWorldTargetCoordinates, double boxHeight) {
@JsonProperty("boxHeight")
private double boxHeight;
TargetModel() {}
TargetModel(MatOfPoint3f realWorldTargetCoordinates, double boxHeight) {
this.realWorldTargetCoordinates = realWorldTargetCoordinates;
this.realWorldCoordinatesArray = realWorldTargetCoordinates.toList();
this.boxHeight = boxHeight;
@@ -53,12 +103,28 @@ public class TargetModel implements Releasable {
}
@JsonCreator
public TargetModel(
TargetModel(
@JsonProperty(value = "realWorldCoordinatesArray") List<Point3> points,
@JsonProperty(value = "boxHeight") double boxHeight) {
this(listToMat(points), boxHeight);
}
public List<Point3> getRealWorldCoordinatesArray() {
return this.realWorldCoordinatesArray;
}
public double getBoxHeight() {
return boxHeight;
}
public void setRealWorldCoordinatesArray(List<Point3> realWorldCoordinatesArray) {
this.realWorldCoordinatesArray = realWorldCoordinatesArray;
}
public void setBoxHeight(double boxHeight) {
this.boxHeight = boxHeight;
}
private static MatOfPoint3f listToMat(List<Point3> points) {
var mat = new MatOfPoint3f();
mat.fromList(points);
@@ -77,58 +143,15 @@ public class TargetModel implements Releasable {
return visualizationBoxTop;
}
public static TargetModel get2020Target() {
return get2020Target(0);
}
public static TargetModel get2020TargetInnerPort() {
// Per the game manual, the inner port is 2ft 5.25in behind the outer port
return get2020Target(Units.inchesToMeters(2d * 12d + 5.25));
}
public static TargetModel get2020Target(double offsetMeters) {
var corners =
List.of(
new Point3(Units.inchesToMeters(-19.625), 0, offsetMeters),
new Point3(Units.inchesToMeters(-9.819867), Units.inchesToMeters(-17), offsetMeters),
new Point3(Units.inchesToMeters(9.819867), Units.inchesToMeters(-17), offsetMeters),
new Point3(Units.inchesToMeters(19.625), 0, offsetMeters));
return new TargetModel(corners, Units.inchesToMeters(12));
}
public static TargetModel get2019Target() {
var corners =
List.of(
new Point3(Units.inchesToMeters(-5.936), Units.inchesToMeters(2.662), 0),
new Point3(Units.inchesToMeters(-7.313), Units.inchesToMeters(-2.662), 0),
new Point3(Units.inchesToMeters(7.313), Units.inchesToMeters(-2.662), 0),
new Point3(Units.inchesToMeters(5.936), Units.inchesToMeters(2.662), 0));
return new TargetModel(corners, 0.1);
}
public static TargetModel getCircleTarget(double radius) {
var corners =
List.of(
new Point3(-radius / 2, -radius / 2, -radius / 2),
new Point3(-radius / 2, radius / 2, -radius / 2),
new Point3(radius / 2, radius / 2, -radius / 2),
new Point3(radius / 2, -radius / 2, -radius / 2));
return new TargetModel(corners, 0);
}
@Override
public boolean equals(Object o) {
if (this == o) return true;
if (!(o instanceof TargetModel)) return false;
TargetModel that = (TargetModel) o;
return Double.compare(that.boxHeight, boxHeight) == 0
&& Objects.equals(realWorldCoordinatesArray, that.realWorldCoordinatesArray);
}
@Override
public int hashCode() {
return Objects.hash(realWorldCoordinatesArray, boxHeight);
}
// public static TargetModel getCircleTarget(double Units.inchesToMeters(7)) {
// var corners =
// List.of(
// new Point3(-Units.inchesToMeters(7) / 2, -radius / 2, -radius / 2),
// new Point3(-Units.inchesToMeters(7) / 2, radius / 2, -radius / 2),
// new Point3(Units.inchesToMeters(7) / 2, radius / 2, -radius / 2),
// new Point3(Units.inchesToMeters(7) / 2, -radius / 2, -radius / 2));
// return new TargetModel(corners, 0);
// }
@Override
public void release() {