Skip to content

Commit 3f095c6

Browse files
committed
Fixed conflicts
1 parent 00ddfe1 commit 3f095c6

File tree

1 file changed

+49
-40
lines changed

1 file changed

+49
-40
lines changed

photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java

+49-40
Original file line numberDiff line numberDiff line change
@@ -226,48 +226,10 @@ private void updatePipelineFromRequested() {
226226
return;
227227
}
228228

229-
// Cleanup potential old native resources before swapping over for user pipelines
230-
if (currentUserPipeline != null && !(newIndex < 0)) {
231-
currentUserPipeline.release();
232-
}
233-
234229
currentPipelineIndex = newIndex;
230+
235231
if (newIndex >= 0) {
236-
var desiredPipelineSettings = userPipelineSettings.get(currentPipelineIndex);
237-
switch (desiredPipelineSettings.pipelineType) {
238-
case Reflective:
239-
logger.debug("Creating Reflective pipeline");
240-
currentUserPipeline =
241-
new ReflectivePipeline((ReflectivePipelineSettings) desiredPipelineSettings);
242-
break;
243-
case ColoredShape:
244-
logger.debug("Creating ColoredShape pipeline");
245-
currentUserPipeline =
246-
new ColoredShapePipeline((ColoredShapePipelineSettings) desiredPipelineSettings);
247-
break;
248-
case AprilTag:
249-
logger.debug("Creating AprilTag pipeline");
250-
currentUserPipeline =
251-
new AprilTagPipeline((AprilTagPipelineSettings) desiredPipelineSettings);
252-
break;
253-
254-
case Aruco:
255-
logger.debug("Creating Aruco Pipeline");
256-
currentUserPipeline = new ArucoPipeline((ArucoPipelineSettings) desiredPipelineSettings);
257-
break;
258-
case RKNN:
259-
logger.debug("Creating RKNN Pipeline");
260-
currentUserPipeline = new RKNNPipeline((RKNNPipelineSettings) desiredPipelineSettings);
261-
break;
262-
case ObjectDetection:
263-
logger.debug("Creating ObjectDetection Pipeline");
264-
currentUserPipeline =
265-
new ObjectDetectionPipeline(
266-
(ObjectDetectionPipelineSettings) desiredPipelineSettings);
267-
default:
268-
// Can be calib3d or drivermode, both of which are special cases
269-
break;
270-
}
232+
recreateUserPipeline();
271233
}
272234

273235
DataChangeService.getInstance()
@@ -384,6 +346,53 @@ private CVPipelineSettings createSettingsForType(PipelineType type, String nickn
384346
}
385347
}
386348
}
349+
350+
/**
351+
* Recreate the current user pipeline with the current pipeline index. Useful to force a
352+
* recreation after changing pipeline type
353+
*/
354+
private void recreateUserPipeline() {
355+
// Cleanup potential old native resources before swapping over from a user pipeline
356+
if (currentUserPipeline != null && !(currentPipelineIndex < 0)) {
357+
currentUserPipeline.release();
358+
}
359+
360+
var desiredPipelineSettings = userPipelineSettings.get(currentPipelineIndex);
361+
switch (desiredPipelineSettings.pipelineType) {
362+
case Reflective:
363+
logger.debug("Creating Reflective pipeline");
364+
currentUserPipeline =
365+
new ReflectivePipeline((ReflectivePipelineSettings) desiredPipelineSettings);
366+
break;
367+
case ColoredShape:
368+
logger.debug("Creating ColoredShape pipeline");
369+
currentUserPipeline =
370+
new ColoredShapePipeline((ColoredShapePipelineSettings) desiredPipelineSettings);
371+
break;
372+
case AprilTag:
373+
logger.debug("Creating AprilTag pipeline");
374+
currentUserPipeline =
375+
new AprilTagPipeline((AprilTagPipelineSettings) desiredPipelineSettings);
376+
break;
377+
378+
case RKNN:
379+
logger.debug("Creating RKNN Pipeline");
380+
currentUserPipeline = new RKNNPipeline((RKNNPipelineSettings) desiredPipelineSettings);
381+
break;
382+
383+
case Aruco:
384+
logger.debug("Creating Aruco Pipeline");
385+
currentUserPipeline = new ArucoPipeline((ArucoPipelineSettings) desiredPipelineSettings);
386+
break;
387+
case ObjectDetection:
388+
logger.debug("Creating ObjectDetection Pipeline");
389+
currentUserPipeline =
390+
new ObjectDetectionPipeline((ObjectDetectionPipelineSettings) desiredPipelineSettings);
391+
default:
392+
// Can be calib3d or drivermode, both of which are special cases
393+
break;
394+
}
395+
}
387396

388397
private void addPipelineInternal(CVPipelineSettings settings) {
389398
settings.pipelineIndex = userPipelineSettings.size();

0 commit comments

Comments
 (0)