Skip to content

Commit

Permalink
Merge branch 'PhotonVision:master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
levyishai authored Mar 19, 2024
2 parents 3f095c6 + c89acea commit 3ffbac3
Show file tree
Hide file tree
Showing 3 changed files with 50 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@ protected List<NeuralNetworkPipeResult> process(CVMat in) {
throw new RuntimeException("RGA bugged but still wrong size");
}
var ret = detector.detect(letterboxed, params.nms, params.confidence);
letterboxed.release();

return resizeDetections(ret, scale);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -238,6 +238,48 @@ private void updatePipelineFromRequested() {
"fullsettings", ConfigManager.getInstance().getConfig().toHashMap()));
}

/**
* Recreate the current user pipeline with the current pipeline index. Useful to force a
* recreation after changing pipeline type
*/
private void recreateUserPipeline() {
// Cleanup potential old native resources before swapping over from a user pipeline
if (currentUserPipeline != null && !(currentPipelineIndex < 0)) {
currentUserPipeline.release();
}

var desiredPipelineSettings = userPipelineSettings.get(currentPipelineIndex);
switch (desiredPipelineSettings.pipelineType) {
case Reflective:
logger.debug("Creating Reflective pipeline");
currentUserPipeline =
new ReflectivePipeline((ReflectivePipelineSettings) desiredPipelineSettings);
break;
case ColoredShape:
logger.debug("Creating ColoredShape pipeline");
currentUserPipeline =
new ColoredShapePipeline((ColoredShapePipelineSettings) desiredPipelineSettings);
break;
case AprilTag:
logger.debug("Creating AprilTag pipeline");
currentUserPipeline =
new AprilTagPipeline((AprilTagPipelineSettings) desiredPipelineSettings);
break;

case Aruco:
logger.debug("Creating Aruco Pipeline");
currentUserPipeline = new ArucoPipeline((ArucoPipelineSettings) desiredPipelineSettings);
break;
case ObjectDetection:
logger.debug("Creating ObjectDetection Pipeline");
currentUserPipeline =
new ObjectDetectionPipeline((ObjectDetectionPipelineSettings) desiredPipelineSettings);
default:
// Can be calib3d or drivermode, both of which are special cases
break;
}
}

/**
* Enters or exits calibration mode based on the parameter. <br>
* <br>
Expand Down Expand Up @@ -521,5 +563,6 @@ public void changePipelineType(int newType) {
userPipelineSettings.set(idx, newSettings);
setPipelineInternal(idx);
reassignIndexes();
recreateUserPipeline();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -96,12 +96,12 @@ class SimCameraProperties {
units::radian_t{std::numbers::pi / 2.0}})
.Radians()}},
frc::Translation3d{
1_m, frc::Rotation3d{0_rad,
(GetPixelPitch(0) +
frc::Rotation2d{
units::radian_t{std::numbers::pi / 2.0}})
.Radians(),
0_rad}},
1_m,
frc::Rotation3d{0_rad,
(GetPixelPitch(0) + frc::Rotation2d{units::radian_t{
std::numbers::pi / 2.0}})
.Radians(),
0_rad}},
frc::Translation3d{
1_m, frc::Rotation3d{0_rad,
(GetPixelPitch(height) +
Expand Down

0 comments on commit 3ffbac3

Please sign in to comment.