mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-21 01:01:41 +00:00
Compare commits
3 Commits
v2024.2.9
...
v2024.2.10
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
d9c2a382f1 | ||
|
|
e125632960 | ||
|
|
d8f82bf9ee |
4
.github/workflows/build.yml
vendored
4
.github/workflows/build.yml
vendored
@@ -367,13 +367,13 @@ jobs:
|
||||
- os: ubuntu-latest
|
||||
artifact-name: LinuxArm64
|
||||
image_suffix: orangepi5
|
||||
image_url: https://github.com/PhotonVision/photon-image-modifier/releases/download/v2024.0.9/photonvision_opi5.img.xz
|
||||
image_url: https://github.com/PhotonVision/photon-image-modifier/releases/download/v2024.0.10/photonvision_opi5.img.xz
|
||||
cpu: cortex-a8
|
||||
image_additional_mb: 4096
|
||||
- os: ubuntu-latest
|
||||
artifact-name: LinuxArm64
|
||||
image_suffix: orangepi5plus
|
||||
image_url: https://github.com/PhotonVision/photon-image-modifier/releases/download/v2024.0.9/photonvision_opi5plus.img.xz
|
||||
image_url: https://github.com/PhotonVision/photon-image-modifier/releases/download/v2024.0.10/photonvision_opi5plus.img.xz
|
||||
cpu: cortex-a8
|
||||
image_additional_mb: 4096
|
||||
|
||||
|
||||
@@ -23,16 +23,37 @@ import java.util.Comparator;
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.objdetect.ArucoDetector;
|
||||
import org.opencv.objdetect.DetectorParameters;
|
||||
import org.opencv.objdetect.Dictionary;
|
||||
import org.opencv.objdetect.Objdetect;
|
||||
import org.photonvision.common.logging.LogGroup;
|
||||
import org.photonvision.common.logging.Logger;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
|
||||
/** This class wraps an {@link ArucoDetector} for convenience. */
|
||||
public class PhotonArucoDetector {
|
||||
public class PhotonArucoDetector implements Releasable {
|
||||
private static final Logger logger = new Logger(PhotonArucoDetector.class, LogGroup.VisionModule);
|
||||
|
||||
private final ArucoDetector detector =
|
||||
new ArucoDetector(Objdetect.getPredefinedDictionary(Objdetect.DICT_APRILTAG_16h5));
|
||||
private static class ArucoDetectorHack extends ArucoDetector {
|
||||
public ArucoDetectorHack(Dictionary predefinedDictionary) {
|
||||
super(predefinedDictionary);
|
||||
}
|
||||
|
||||
// avoid double-free by keeping track of this ourselves (ew)
|
||||
private boolean freed = false;
|
||||
|
||||
@Override
|
||||
public void finalize() throws Throwable {
|
||||
if (freed) {
|
||||
return;
|
||||
}
|
||||
|
||||
super.finalize();
|
||||
freed = true;
|
||||
}
|
||||
}
|
||||
|
||||
private final ArucoDetectorHack detector =
|
||||
new ArucoDetectorHack(Objdetect.getPredefinedDictionary(Objdetect.DICT_APRILTAG_16h5));
|
||||
|
||||
private final Mat ids = new Mat();
|
||||
private final ArrayList<Mat> cornerMats = new ArrayList<>();
|
||||
@@ -95,4 +116,16 @@ public class PhotonArucoDetector {
|
||||
|
||||
return results;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
try {
|
||||
detector.finalize();
|
||||
} catch (Throwable e) {
|
||||
logger.error("Exception destroying PhotonArucoDetector", e);
|
||||
}
|
||||
ids.release();
|
||||
for (var m : cornerMats) m.release();
|
||||
cornerMats.clear();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -33,7 +33,7 @@ import org.photonvision.vision.opencv.CVMat;
|
||||
* path}.
|
||||
*/
|
||||
public class FileFrameProvider extends CpuImageProcessor {
|
||||
public static final int MAX_FPS = 5;
|
||||
public static final int MAX_FPS = 10;
|
||||
private static int count = 0;
|
||||
|
||||
private final int thisIndex = count++;
|
||||
|
||||
@@ -21,11 +21,13 @@ import edu.wpi.first.apriltag.AprilTagDetection;
|
||||
import edu.wpi.first.apriltag.AprilTagDetector;
|
||||
import java.util.List;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
import org.photonvision.vision.pipe.CVPipe;
|
||||
|
||||
public class AprilTagDetectionPipe
|
||||
extends CVPipe<CVMat, List<AprilTagDetection>, AprilTagDetectionPipeParams> {
|
||||
private final AprilTagDetector m_detector = new AprilTagDetector();
|
||||
extends CVPipe<CVMat, List<AprilTagDetection>, AprilTagDetectionPipeParams>
|
||||
implements Releasable {
|
||||
private AprilTagDetector m_detector = new AprilTagDetector();
|
||||
|
||||
public AprilTagDetectionPipe() {
|
||||
super();
|
||||
@@ -40,6 +42,10 @@ public class AprilTagDetectionPipe
|
||||
return List.of();
|
||||
}
|
||||
|
||||
if (m_detector == null) {
|
||||
throw new RuntimeException("Apriltag detector was released!");
|
||||
}
|
||||
|
||||
var ret = m_detector.detect(in.getMat());
|
||||
|
||||
if (ret == null) {
|
||||
@@ -60,4 +66,10 @@ public class AprilTagDetectionPipe
|
||||
|
||||
super.setParams(newParams);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
m_detector.close();
|
||||
m_detector = null;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -25,13 +25,15 @@ import org.opencv.calib3d.Calib3d;
|
||||
import org.opencv.core.MatOfPoint2f;
|
||||
import org.opencv.core.Point;
|
||||
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
import org.photonvision.vision.pipe.CVPipe;
|
||||
|
||||
public class AprilTagPoseEstimatorPipe
|
||||
extends CVPipe<
|
||||
AprilTagDetection,
|
||||
AprilTagPoseEstimate,
|
||||
AprilTagPoseEstimatorPipe.AprilTagPoseEstimatorPipeParams> {
|
||||
AprilTagPoseEstimatorPipe.AprilTagPoseEstimatorPipeParams>
|
||||
implements Releasable {
|
||||
private final AprilTagPoseEstimator m_poseEstimator =
|
||||
new AprilTagPoseEstimator(new AprilTagPoseEstimator.Config(0, 0, 0, 0, 0));
|
||||
|
||||
@@ -92,6 +94,11 @@ public class AprilTagPoseEstimatorPipe
|
||||
super.setParams(newParams);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
temp.release();
|
||||
}
|
||||
|
||||
public static class AprilTagPoseEstimatorPipeParams {
|
||||
final AprilTagPoseEstimator.Config config;
|
||||
final CameraCalibrationCoefficients calibration;
|
||||
|
||||
@@ -29,10 +29,12 @@ import org.opencv.objdetect.Objdetect;
|
||||
import org.photonvision.vision.aruco.ArucoDetectionResult;
|
||||
import org.photonvision.vision.aruco.PhotonArucoDetector;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
import org.photonvision.vision.pipe.CVPipe;
|
||||
|
||||
public class ArucoDetectionPipe
|
||||
extends CVPipe<CVMat, List<ArucoDetectionResult>, ArucoDetectionPipeParams> {
|
||||
extends CVPipe<CVMat, List<ArucoDetectionResult>, ArucoDetectionPipeParams>
|
||||
implements Releasable {
|
||||
// ArucoDetector wrapper class
|
||||
private final PhotonArucoDetector photonDetector = new PhotonArucoDetector();
|
||||
|
||||
@@ -131,4 +133,9 @@ public class ArucoDetectionPipe
|
||||
var pt2 = new Point(corner.x + windowSize, corner.y + windowSize);
|
||||
Imgproc.rectangle(outputMat, pt1, pt2, new Scalar(0, 0, 255), thickness);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
photonDetector.release();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -32,13 +32,15 @@ import org.opencv.core.MatOfPoint3f;
|
||||
import org.opencv.core.Point3;
|
||||
import org.photonvision.vision.aruco.ArucoDetectionResult;
|
||||
import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
import org.photonvision.vision.opencv.Releasable;
|
||||
import org.photonvision.vision.pipe.CVPipe;
|
||||
|
||||
public class ArucoPoseEstimatorPipe
|
||||
extends CVPipe<
|
||||
ArucoDetectionResult,
|
||||
AprilTagPoseEstimate,
|
||||
ArucoPoseEstimatorPipe.ArucoPoseEstimatorPipeParams> {
|
||||
ArucoPoseEstimatorPipe.ArucoPoseEstimatorPipeParams>
|
||||
implements Releasable {
|
||||
// image points of marker corners
|
||||
private final MatOfPoint2f imagePoints = new MatOfPoint2f(Mat.zeros(4, 1, CvType.CV_32FC2));
|
||||
// rvec/tvec estimations from solvepnp
|
||||
@@ -117,6 +119,18 @@ public class ArucoPoseEstimatorPipe
|
||||
super.setParams(newParams);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
imagePoints.release();
|
||||
for (var m : rvecs) m.release();
|
||||
rvecs.clear();
|
||||
for (var m : tvecs) m.release();
|
||||
tvecs.clear();
|
||||
rvec.release();
|
||||
tvec.release();
|
||||
reprojectionErrors.release();
|
||||
}
|
||||
|
||||
public static class ArucoPoseEstimatorPipeParams {
|
||||
final CameraCalibrationCoefficients calibration;
|
||||
final double tagSize;
|
||||
|
||||
@@ -38,13 +38,26 @@ import org.photonvision.vision.calibration.CameraCalibrationCoefficients;
|
||||
import org.photonvision.vision.calibration.CameraLensModel;
|
||||
import org.photonvision.vision.calibration.JsonImageMat;
|
||||
import org.photonvision.vision.calibration.JsonMatOfDouble;
|
||||
import org.photonvision.vision.frame.FrameStaticProperties;
|
||||
import org.photonvision.vision.pipe.CVPipe;
|
||||
import org.photonvision.vision.pipe.impl.FindBoardCornersPipe.FindBoardCornersPipeResult;
|
||||
|
||||
public class Calibrate3dPipe
|
||||
extends CVPipe<
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult>,
|
||||
Calibrate3dPipe.CalibrationInput,
|
||||
CameraCalibrationCoefficients,
|
||||
Calibrate3dPipe.CalibratePipeParams> {
|
||||
public static class CalibrationInput {
|
||||
final List<FindBoardCornersPipe.FindBoardCornersPipeResult> observations;
|
||||
final FrameStaticProperties imageProps;
|
||||
|
||||
public CalibrationInput(
|
||||
List<FindBoardCornersPipeResult> observations, FrameStaticProperties imageProps) {
|
||||
this.observations = observations;
|
||||
this.imageProps = imageProps;
|
||||
}
|
||||
}
|
||||
|
||||
// For logging
|
||||
private static final Logger logger = new Logger(Calibrate3dPipe.class, LogGroup.General);
|
||||
|
||||
@@ -63,10 +76,9 @@ public class Calibrate3dPipe
|
||||
* @return Result of processing.
|
||||
*/
|
||||
@Override
|
||||
protected CameraCalibrationCoefficients process(
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult> in) {
|
||||
in =
|
||||
in.stream()
|
||||
protected CameraCalibrationCoefficients process(CalibrationInput in) {
|
||||
var filteredIn =
|
||||
in.observations.stream()
|
||||
.filter(
|
||||
it ->
|
||||
it != null
|
||||
@@ -79,17 +91,21 @@ public class Calibrate3dPipe
|
||||
var start = System.nanoTime();
|
||||
if (MrCalJNILoader.getInstance().isLoaded() && params.useMrCal) {
|
||||
logger.debug("Calibrating with mrcal!");
|
||||
ret = calibrateMrcal(in);
|
||||
ret =
|
||||
calibrateMrcal(
|
||||
filteredIn, in.imageProps.horizontalFocalLength, in.imageProps.verticalFocalLength);
|
||||
} else {
|
||||
logger.debug("Calibrating with opencv!");
|
||||
ret = calibrateOpenCV(in);
|
||||
ret =
|
||||
calibrateOpenCV(
|
||||
filteredIn, in.imageProps.horizontalFocalLength, in.imageProps.verticalFocalLength);
|
||||
}
|
||||
var dt = System.nanoTime() - start;
|
||||
|
||||
if (ret != null)
|
||||
logger.info(
|
||||
"CALIBRATION SUCCESS for res "
|
||||
+ in.get(0).size
|
||||
+ in.observations.get(0).size
|
||||
+ " in "
|
||||
+ dt / 1e6
|
||||
+ "ms! camMatrix: \n"
|
||||
@@ -103,7 +119,7 @@ public class Calibrate3dPipe
|
||||
}
|
||||
|
||||
protected CameraCalibrationCoefficients calibrateOpenCV(
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult> in) {
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult> in, double fxGuess, double fyGuess) {
|
||||
List<Mat> objPoints = in.stream().map(it -> it.objectPoints).collect(Collectors.toList());
|
||||
List<Mat> imgPts = in.stream().map(it -> it.imagePoints).collect(Collectors.toList());
|
||||
if (objPoints.size() != imgPts.size()) {
|
||||
@@ -111,30 +127,32 @@ public class Calibrate3dPipe
|
||||
return null;
|
||||
}
|
||||
|
||||
Mat cameraMatrix = new Mat();
|
||||
Mat cameraMatrix = new Mat(3, 3, CvType.CV_64F);
|
||||
MatOfDouble distortionCoefficients = new MatOfDouble();
|
||||
List<Mat> rvecs = new ArrayList<>();
|
||||
List<Mat> tvecs = new ArrayList<>();
|
||||
|
||||
// RMS of the calibration
|
||||
double calibrationAccuracy;
|
||||
// initial camera matrix guess
|
||||
double cx = (in.get(0).size.width / 2.0) - 0.5;
|
||||
double cy = (in.get(0).size.width / 2.0) - 0.5;
|
||||
cameraMatrix.put(0, 0, new double[] {fxGuess, 0, cx, 0, fyGuess, cy, 0, 0, 1});
|
||||
|
||||
try {
|
||||
// FindBoardCorners pipe outputs all the image points, object points, and frames to calculate
|
||||
// imageSize from, other parameters are output Mats
|
||||
|
||||
calibrationAccuracy =
|
||||
Calib3d.calibrateCameraExtended(
|
||||
objPoints,
|
||||
imgPts,
|
||||
new Size(in.get(0).size.width, in.get(0).size.height),
|
||||
cameraMatrix,
|
||||
distortionCoefficients,
|
||||
rvecs,
|
||||
tvecs,
|
||||
stdDeviationsIntrinsics,
|
||||
stdDeviationsExtrinsics,
|
||||
perViewErrors);
|
||||
Calib3d.calibrateCameraExtended(
|
||||
objPoints,
|
||||
imgPts,
|
||||
new Size(in.get(0).size.width, in.get(0).size.height),
|
||||
cameraMatrix,
|
||||
distortionCoefficients,
|
||||
rvecs,
|
||||
tvecs,
|
||||
stdDeviationsIntrinsics,
|
||||
stdDeviationsExtrinsics,
|
||||
perViewErrors,
|
||||
Calib3d.CALIB_USE_LU + Calib3d.CALIB_USE_INTRINSIC_GUESS);
|
||||
} catch (Exception e) {
|
||||
logger.error("Calibration failed!", e);
|
||||
e.printStackTrace();
|
||||
@@ -164,13 +182,12 @@ public class Calibrate3dPipe
|
||||
}
|
||||
|
||||
protected CameraCalibrationCoefficients calibrateMrcal(
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult> in) {
|
||||
List<FindBoardCornersPipe.FindBoardCornersPipeResult> in, double fxGuess, double fyGuess) {
|
||||
List<MatOfPoint2f> corner_locations =
|
||||
in.stream().map(it -> it.imagePoints).map(MatOfPoint2f::new).collect(Collectors.toList());
|
||||
|
||||
int imageWidth = (int) in.get(0).size.width;
|
||||
int imageHeight = (int) in.get(0).size.height;
|
||||
final double FOCAL_LENGTH_GUESS = 1200;
|
||||
|
||||
MrCalResult result =
|
||||
MrCalJNI.calibrateCamera(
|
||||
@@ -180,7 +197,7 @@ public class Calibrate3dPipe
|
||||
params.squareSize,
|
||||
imageWidth,
|
||||
imageHeight,
|
||||
FOCAL_LENGTH_GUESS);
|
||||
(fxGuess + fyGuess) / 2.0);
|
||||
|
||||
// intrinsics are fx fy cx cy from mrcal
|
||||
JsonMatOfDouble cameraMatrixMat =
|
||||
|
||||
@@ -36,6 +36,7 @@ import org.photonvision.vision.frame.FrameThresholdType;
|
||||
import org.photonvision.vision.opencv.CVMat;
|
||||
import org.photonvision.vision.opencv.ImageRotationMode;
|
||||
import org.photonvision.vision.pipe.CVPipe.CVPipeResult;
|
||||
import org.photonvision.vision.pipe.impl.Calibrate3dPipe.CalibrationInput;
|
||||
import org.photonvision.vision.pipe.impl.FindBoardCornersPipe.FindBoardCornersPipeResult;
|
||||
import org.photonvision.vision.pipeline.CVPipeline;
|
||||
import org.photonvision.vision.pipeline.Calibration3dPipelineSettings;
|
||||
@@ -176,7 +177,8 @@ public class Calibrate3dPipeline
|
||||
|
||||
/*Pass the board corners to the pipe, which will check again to see if all boards are valid
|
||||
and returns the corresponding image and object points*/
|
||||
calibrationOutput = calibrate3dPipe.run(foundCornersList);
|
||||
calibrationOutput =
|
||||
calibrate3dPipe.run(new CalibrationInput(foundCornersList, frameStaticProperties));
|
||||
|
||||
this.calibrating = false;
|
||||
|
||||
@@ -229,4 +231,9 @@ public class Calibrate3dPipeline
|
||||
public CameraCalibrationCoefficients cameraCalibrationCoefficients() {
|
||||
return calibrationOutput.output;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
// we never actually need to give resources up since pipelinemanager only makes one of us
|
||||
}
|
||||
}
|
||||
|
||||
@@ -221,4 +221,11 @@ public class AprilTagPipeline extends CVPipeline<CVPipelineResult, AprilTagPipel
|
||||
|
||||
return new CVPipelineResult(sumPipeNanosElapsed, fps, targetList, multiTagResult, frame);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
aprilTagDetectionPipe.release();
|
||||
singleTagPoseEstimatorPipe.release();
|
||||
super.release();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -60,8 +60,8 @@ import org.photonvision.vision.target.TrackedTarget;
|
||||
import org.photonvision.vision.target.TrackedTarget.TargetCalculationParameters;
|
||||
|
||||
public class ArucoPipeline extends CVPipeline<CVPipelineResult, ArucoPipelineSettings> {
|
||||
private final ArucoDetectionPipe arucoDetectionPipe = new ArucoDetectionPipe();
|
||||
private final ArucoPoseEstimatorPipe singleTagPoseEstimatorPipe = new ArucoPoseEstimatorPipe();
|
||||
private ArucoDetectionPipe arucoDetectionPipe = new ArucoDetectionPipe();
|
||||
private ArucoPoseEstimatorPipe singleTagPoseEstimatorPipe = new ArucoPoseEstimatorPipe();
|
||||
private final MultiTargetPNPPipe multiTagPNPPipe = new MultiTargetPNPPipe();
|
||||
private final CalculateFPSPipe calculateFPSPipe = new CalculateFPSPipe();
|
||||
|
||||
@@ -250,4 +250,13 @@ public class ArucoPipeline extends CVPipeline<CVPipelineResult, ArucoPipelineSet
|
||||
windowSize,
|
||||
constant);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
arucoDetectionPipe.release();
|
||||
singleTagPoseEstimatorPipe.release();
|
||||
arucoDetectionPipe = null;
|
||||
singleTagPoseEstimatorPipe = null;
|
||||
super.release();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -34,6 +34,9 @@ public abstract class CVPipeline<R extends CVPipelineResult, S extends CVPipelin
|
||||
|
||||
private final FrameThresholdType thresholdType;
|
||||
|
||||
// So releaseable doesn't keep track of if we double-free something. so (ew) remember that here
|
||||
protected volatile boolean released = false;
|
||||
|
||||
public CVPipeline(FrameThresholdType thresholdType) {
|
||||
this.thresholdType = thresholdType;
|
||||
}
|
||||
@@ -64,6 +67,9 @@ public abstract class CVPipeline<R extends CVPipelineResult, S extends CVPipelin
|
||||
}
|
||||
|
||||
public R run(Frame frame, QuirkyCamera cameraQuirks) {
|
||||
if (released) {
|
||||
throw new RuntimeException("Pipeline use-after-free!");
|
||||
}
|
||||
if (settings == null) {
|
||||
throw new RuntimeException("No settings provided for pipeline!");
|
||||
}
|
||||
@@ -85,5 +91,7 @@ public abstract class CVPipeline<R extends CVPipelineResult, S extends CVPipelin
|
||||
* switch. Stubbed out, but override if needed.
|
||||
*/
|
||||
@Override
|
||||
public void release() {}
|
||||
public void release() {
|
||||
released = true;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -88,4 +88,9 @@ public class DriverModePipeline
|
||||
fps,
|
||||
new Frame(frame.processedImage, frame.colorImage, frame.type, frame.frameStaticProperties));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void release() {
|
||||
// we never actually need to give resources up since pipelinemanager only makes one of us
|
||||
}
|
||||
}
|
||||
|
||||
@@ -131,5 +131,6 @@ public class ObjectDetectionPipeline
|
||||
@Override
|
||||
public void release() {
|
||||
rknnPipe.release();
|
||||
super.release();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -148,6 +148,7 @@ public class PipelineManager {
|
||||
* @return The currently active pipeline.
|
||||
*/
|
||||
public CVPipeline getCurrentPipeline() {
|
||||
updatePipelineFromRequested();
|
||||
if (currentPipelineIndex < 0) {
|
||||
switch (currentPipelineIndex) {
|
||||
case CAL_3D_INDEX:
|
||||
@@ -170,6 +171,8 @@ public class PipelineManager {
|
||||
return getPipelineSettings(currentPipelineIndex);
|
||||
}
|
||||
|
||||
private volatile int requestedIndex = 0;
|
||||
|
||||
/**
|
||||
* Internal method for setting the active pipeline. <br>
|
||||
* <br>
|
||||
@@ -179,6 +182,22 @@ public class PipelineManager {
|
||||
* @param newIndex Index of pipeline to be active
|
||||
*/
|
||||
private void setPipelineInternal(int newIndex) {
|
||||
requestedIndex = newIndex;
|
||||
}
|
||||
|
||||
/**
|
||||
* Based on a requested pipeline index, create/destroy pipelines as necessary. We do this as a
|
||||
* side effect of the main thread that calls getCurrentPipeline to avoid race conditions between
|
||||
* server threads and the VisionRunner TODO: this should be refactored. Shame Java doesn't have
|
||||
* RAII
|
||||
*/
|
||||
private void updatePipelineFromRequested() {
|
||||
int newIndex = requestedIndex;
|
||||
if (newIndex == currentPipelineIndex) {
|
||||
// nothing to do, probably no change -- give up
|
||||
return;
|
||||
}
|
||||
|
||||
if (newIndex < 0 && currentPipelineIndex >= 0) {
|
||||
// Transitioning to a built-in pipe, save off the current user one
|
||||
lastUserPipelineIdx = currentPipelineIndex;
|
||||
@@ -189,8 +208,8 @@ public class PipelineManager {
|
||||
return;
|
||||
}
|
||||
|
||||
// Cleanup potential old native resources before swapping over
|
||||
if (currentUserPipeline != null) {
|
||||
// Cleanup potential old native resources before swapping over for user pipelines
|
||||
if (currentUserPipeline != null && !(newIndex < 0)) {
|
||||
currentUserPipeline.release();
|
||||
}
|
||||
|
||||
|
||||
@@ -277,7 +277,7 @@ public class Main {
|
||||
|
||||
CameraConfiguration camConf2024 =
|
||||
ConfigManager.getInstance().getConfig().getCameraConfigurations().get("WPI2024");
|
||||
if (camConf2024 == null || true) {
|
||||
if (camConf2024 == null) {
|
||||
camConf2024 =
|
||||
new CameraConfiguration(
|
||||
"WPI2024",
|
||||
|
||||
Reference in New Issue
Block a user