mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
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:
@@ -1,52 +0,0 @@
|
||||
{
|
||||
"2020 Hex Goal": {
|
||||
"realWorldCoordinatesArray": [
|
||||
{
|
||||
"x": -0.49847498536109924,
|
||||
"y": 0.0,
|
||||
"z": 0.0
|
||||
},
|
||||
{
|
||||
"x": -0.24942462146282196,
|
||||
"y": -0.4318000078201294,
|
||||
"z": 0.0
|
||||
},
|
||||
{
|
||||
"x": 0.24942462146282196,
|
||||
"y": -0.4318000078201294,
|
||||
"z": 0.0
|
||||
},
|
||||
{
|
||||
"x": 0.49847498536109924,
|
||||
"y": 0.0,
|
||||
"z": 0.0
|
||||
}
|
||||
],
|
||||
"boxHeight": 0.30479999999999996
|
||||
},
|
||||
"2019 Dual Target": {
|
||||
"realWorldCoordinatesArray": [
|
||||
{
|
||||
"x": -0.15077440440654755,
|
||||
"y": 0.06761480122804642,
|
||||
"z": 0.0
|
||||
},
|
||||
{
|
||||
"x": -0.18575020134449005,
|
||||
"y": -0.06761480122804642,
|
||||
"z": 0.0
|
||||
},
|
||||
{
|
||||
"x": 0.18575020134449005,
|
||||
"y": -0.06761480122804642,
|
||||
"z": 0.0
|
||||
},
|
||||
{
|
||||
"x": 0.15077440440654755,
|
||||
"y": 0.06761480122804642,
|
||||
"z": 0.0
|
||||
}
|
||||
],
|
||||
"boxHeight": 0.1
|
||||
}
|
||||
}
|
||||
@@ -122,8 +122,8 @@ export default new Vuex.Store({
|
||||
minCount: 25,
|
||||
hasEnough: false,
|
||||
squareSizeIn: 1.0,
|
||||
patternWidth: 7,
|
||||
patternHeight: 7,
|
||||
patternWidth: 8,
|
||||
patternHeight: 8,
|
||||
boardType: 0, // Chessboard, dotboard
|
||||
},
|
||||
metrics: {
|
||||
|
||||
@@ -93,14 +93,14 @@
|
||||
v-model="boardWidth"
|
||||
name="Board width"
|
||||
label-cols="5"
|
||||
tooltip="Width of the board in dots or corners; with the standard chessboard, this is usually 7"
|
||||
tooltip="Width of the board in dots or chessboard squares; with the standard chessboard, this is usually 8"
|
||||
:disabled="isCalibrating"
|
||||
/>
|
||||
<CVnumberinput
|
||||
v-model="boardHeight"
|
||||
name="Board height"
|
||||
label-cols="5"
|
||||
tooltip="Height of the board in dots or corners; with the standard chessboard, this is usually 7"
|
||||
tooltip="Height of the board in dots or chessboard squares; with the standard chessboard, this is usually 8"
|
||||
:disabled="isCalibrating"
|
||||
/>
|
||||
</v-col>
|
||||
@@ -291,7 +291,7 @@ export default {
|
||||
text: ""
|
||||
},
|
||||
snack: false,
|
||||
filteredVideomodeIndex: 0
|
||||
filteredVideomodeIndex: undefined,
|
||||
}
|
||||
},
|
||||
computed: {
|
||||
@@ -409,7 +409,6 @@ export default {
|
||||
return this.$store.getters.currentPipelineIndex === -2;
|
||||
}
|
||||
},
|
||||
|
||||
selectedFilteredResIndex: {
|
||||
get() {
|
||||
return this.filteredVideomodeIndex
|
||||
|
||||
@@ -16,10 +16,10 @@
|
||||
color="accent"
|
||||
item-color="secondary"
|
||||
label="Select a target model"
|
||||
:items="FRCtargets"
|
||||
:items="targetList"
|
||||
item-text="name"
|
||||
item-value="data"
|
||||
@change="onModelSelect"
|
||||
@input="handlePipelineUpdate('targetModel', targetList.indexOf(selectedModel))"
|
||||
/>
|
||||
<CVslider
|
||||
v-model="cornerDetectionAccuracyPercentage"
|
||||
@@ -51,7 +51,6 @@
|
||||
import Papa from 'papaparse';
|
||||
import miniMap from '../../components/pipeline/3D/MiniMap';
|
||||
import CVslider from '../../components/common/cv-slider'
|
||||
import FRCtargetsConfig from '../../assets/FRCtargets'
|
||||
|
||||
export default {
|
||||
name: "SolvePNP",
|
||||
@@ -61,18 +60,25 @@
|
||||
},
|
||||
data() {
|
||||
return {
|
||||
FRCtargets: null,
|
||||
targetList: ['2020 High Goal Outer', '2020 High Goal Inner', '2019 Dual Target', 'Power Cell (7in)'],
|
||||
snackbar: {
|
||||
color: "Success",
|
||||
text: ""
|
||||
},
|
||||
snack: false,
|
||||
selectedModel: {
|
||||
isCustom: false
|
||||
}
|
||||
}
|
||||
},
|
||||
computed: {
|
||||
selectedModel: {
|
||||
get() {
|
||||
let ret = this.$store.getters.currentPipelineSettings.targetModel
|
||||
console.log(ret)
|
||||
return this.targetList[ret];
|
||||
},
|
||||
set(val) {
|
||||
this.$store.commit("mutatePipeline", {"targetModel": this.targetList.indexOf(val)})
|
||||
}
|
||||
},
|
||||
cornerDetectionAccuracyPercentage: {
|
||||
get() {
|
||||
return this.$store.getters.currentPipelineSettings.cornerDetectionAccuracyPercentage
|
||||
@@ -97,20 +103,6 @@
|
||||
}
|
||||
},
|
||||
},
|
||||
mounted() {
|
||||
let tmp = [];
|
||||
for (let t in FRCtargetsConfig) {
|
||||
if (FRCtargetsConfig.hasOwnProperty(t)) {
|
||||
tmp.push({name: t, data: FRCtargetsConfig[t]});
|
||||
}
|
||||
}
|
||||
|
||||
// Special dropdown item for uploading your own model
|
||||
// data is what gets put in selectedMode, so we add a special field
|
||||
tmp.push({name: "Custom model", data: {isCustom: true}});
|
||||
|
||||
this.FRCtargets = tmp;
|
||||
},
|
||||
methods: {
|
||||
readFile(event) {
|
||||
let file = event.target.files[0];
|
||||
@@ -119,13 +111,6 @@
|
||||
skipEmptyLines: true
|
||||
});
|
||||
},
|
||||
onModelSelect() {
|
||||
if (this.selectedModel.isCustom) {
|
||||
this.$refs.file.click();
|
||||
} else {
|
||||
this.uploadPremade();
|
||||
}
|
||||
},
|
||||
onParse(result) {
|
||||
if (result.data.length > 0) {
|
||||
let data = [];
|
||||
@@ -158,29 +143,6 @@
|
||||
this.selectedModel = null;
|
||||
}
|
||||
},
|
||||
uploadPremade() {
|
||||
this.uploadModel(this.selectedModel, true);
|
||||
},
|
||||
uploadModel(model, premade = false) {
|
||||
this.axios.post("http://" + this.$address + "/api/vision/pnpModel", {
|
||||
['targetModel']: model,
|
||||
['index']: this.$store.getters.currentCameraIndex
|
||||
}).then(() => {
|
||||
this.snackbar = {
|
||||
color: "success",
|
||||
text: premade ? "Target model changed successfully" : "Custom target model uploaded and selected successfully"
|
||||
};
|
||||
this.snack = true;
|
||||
}).catch(() => {
|
||||
this.snackbar = {
|
||||
color: "error",
|
||||
text: "An error occurred selecting a target model"
|
||||
};
|
||||
this.snack = true;
|
||||
|
||||
this.selectedModel = null;
|
||||
});
|
||||
}
|
||||
}
|
||||
}
|
||||
</script>
|
||||
|
||||
@@ -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>();
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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);
|
||||
|
||||
|
||||
@@ -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 =
|
||||
|
||||
@@ -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() {
|
||||
|
||||
@@ -54,7 +54,7 @@ public class ConfigTest {
|
||||
COLORED_SHAPE_PIPELINE_SETTINGS = new ColoredShapePipelineSettings();
|
||||
|
||||
REFLECTIVE_PIPELINE_SETTINGS.pipelineNickname = "2019Tape";
|
||||
REFLECTIVE_PIPELINE_SETTINGS.targetModel = TargetModel.get2019Target();
|
||||
REFLECTIVE_PIPELINE_SETTINGS.targetModel = TargetModel.k2019DualTarget;
|
||||
|
||||
COLORED_SHAPE_PIPELINE_SETTINGS.pipelineNickname = "2019Cargo";
|
||||
COLORED_SHAPE_PIPELINE_SETTINGS.pipelineIndex = 1;
|
||||
|
||||
@@ -97,7 +97,7 @@ public class CirclePNPTest {
|
||||
pipeline.getSettings().cornerDetectionAccuracyPercentage = 4;
|
||||
pipeline.getSettings().cornerDetectionUseConvexHulls = true;
|
||||
pipeline.getSettings().cameraCalibration = getCoeffs(LIFECAM_480P_CAL_FILE);
|
||||
pipeline.getSettings().targetModel = TargetModel.getCircleTarget(7);
|
||||
pipeline.getSettings().targetModel = TargetModel.kCircularPowerCell7in;
|
||||
pipeline.getSettings().cameraPitch = Rotation2d.fromDegrees(0.0);
|
||||
pipeline.getSettings().outputShouldDraw = true;
|
||||
pipeline.getSettings().outputShowMultipleTargets = false;
|
||||
|
||||
@@ -98,7 +98,7 @@ public class SolvePNPTest {
|
||||
pipeline.getSettings().contourGroupingMode = ContourGroupingMode.Dual;
|
||||
pipeline.getSettings().contourIntersection = ContourIntersectionDirection.Up;
|
||||
pipeline.getSettings().cornerDetectionUseConvexHulls = true;
|
||||
pipeline.getSettings().targetModel = TargetModel.get2019Target();
|
||||
pipeline.getSettings().targetModel = TargetModel.k2019DualTarget;
|
||||
|
||||
var frameProvider =
|
||||
new FileFrameProvider(
|
||||
@@ -133,7 +133,7 @@ public class SolvePNPTest {
|
||||
pipeline.getSettings().solvePNPEnabled = true;
|
||||
pipeline.getSettings().cornerDetectionAccuracyPercentage = 4;
|
||||
pipeline.getSettings().cornerDetectionUseConvexHulls = true;
|
||||
pipeline.getSettings().targetModel = TargetModel.get2020Target();
|
||||
pipeline.getSettings().targetModel = TargetModel.k2020HighGoalOuter;
|
||||
|
||||
var frameProvider =
|
||||
new FileFrameProvider(
|
||||
|
||||
@@ -15,7 +15,6 @@
|
||||
"cpuMemoryCommand" : "echo 10",
|
||||
"cpuUtilCommand" : "echo 10",
|
||||
"gpuMemoryCommand" : "echo 10",
|
||||
"gpuTempCommand" : "echo 10",
|
||||
"ramUtilCommand" : "echo 10",
|
||||
"restartHardwareCommand" : "echo 10",
|
||||
"vendorFOV" : 40.0
|
||||
|
||||
Reference in New Issue
Block a user