Skip to content

Commit 3ffbac3

Browse files
authoredMar 19, 2024
Merge branch 'PhotonVision:master' into master
2 parents 3f095c6 + c89acea commit 3ffbac3

File tree

3 files changed

+50
-6
lines changed

3 files changed

+50
-6
lines changed
 

‎photon-core/src/main/java/org/photonvision/vision/pipe/impl/RknnDetectionPipe.java

+1
Original file line numberDiff line numberDiff line change
@@ -81,6 +81,7 @@ protected List<NeuralNetworkPipeResult> process(CVMat in) {
8181
throw new RuntimeException("RGA bugged but still wrong size");
8282
}
8383
var ret = detector.detect(letterboxed, params.nms, params.confidence);
84+
letterboxed.release();
8485

8586
return resizeDetections(ret, scale);
8687
}

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

+43
Original file line numberDiff line numberDiff line change
@@ -238,6 +238,48 @@ private void updatePipelineFromRequested() {
238238
"fullsettings", ConfigManager.getInstance().getConfig().toHashMap()));
239239
}
240240

241+
/**
242+
* Recreate the current user pipeline with the current pipeline index. Useful to force a
243+
* recreation after changing pipeline type
244+
*/
245+
private void recreateUserPipeline() {
246+
// Cleanup potential old native resources before swapping over from a user pipeline
247+
if (currentUserPipeline != null && !(currentPipelineIndex < 0)) {
248+
currentUserPipeline.release();
249+
}
250+
251+
var desiredPipelineSettings = userPipelineSettings.get(currentPipelineIndex);
252+
switch (desiredPipelineSettings.pipelineType) {
253+
case Reflective:
254+
logger.debug("Creating Reflective pipeline");
255+
currentUserPipeline =
256+
new ReflectivePipeline((ReflectivePipelineSettings) desiredPipelineSettings);
257+
break;
258+
case ColoredShape:
259+
logger.debug("Creating ColoredShape pipeline");
260+
currentUserPipeline =
261+
new ColoredShapePipeline((ColoredShapePipelineSettings) desiredPipelineSettings);
262+
break;
263+
case AprilTag:
264+
logger.debug("Creating AprilTag pipeline");
265+
currentUserPipeline =
266+
new AprilTagPipeline((AprilTagPipelineSettings) desiredPipelineSettings);
267+
break;
268+
269+
case Aruco:
270+
logger.debug("Creating Aruco Pipeline");
271+
currentUserPipeline = new ArucoPipeline((ArucoPipelineSettings) desiredPipelineSettings);
272+
break;
273+
case ObjectDetection:
274+
logger.debug("Creating ObjectDetection Pipeline");
275+
currentUserPipeline =
276+
new ObjectDetectionPipeline((ObjectDetectionPipelineSettings) desiredPipelineSettings);
277+
default:
278+
// Can be calib3d or drivermode, both of which are special cases
279+
break;
280+
}
281+
}
282+
241283
/**
242284
* Enters or exits calibration mode based on the parameter. <br>
243285
* <br>
@@ -521,5 +563,6 @@ public void changePipelineType(int newType) {
521563
userPipelineSettings.set(idx, newSettings);
522564
setPipelineInternal(idx);
523565
reassignIndexes();
566+
recreateUserPipeline();
524567
}
525568
}

‎photon-lib/src/main/native/include/photon/simulation/SimCameraProperties.h

+6-6
Original file line numberDiff line numberDiff line change
@@ -96,12 +96,12 @@ class SimCameraProperties {
9696
units::radian_t{std::numbers::pi / 2.0}})
9797
.Radians()}},
9898
frc::Translation3d{
99-
1_m, frc::Rotation3d{0_rad,
100-
(GetPixelPitch(0) +
101-
frc::Rotation2d{
102-
units::radian_t{std::numbers::pi / 2.0}})
103-
.Radians(),
104-
0_rad}},
99+
1_m,
100+
frc::Rotation3d{0_rad,
101+
(GetPixelPitch(0) + frc::Rotation2d{units::radian_t{
102+
std::numbers::pi / 2.0}})
103+
.Radians(),
104+
0_rad}},
105105
frc::Translation3d{
106106
1_m, frc::Rotation3d{0_rad,
107107
(GetPixelPitch(height) +

0 commit comments

Comments
 (0)