mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-19 00:41:41 +00:00
Aruco/Multitag 36h11 support (#981)
- Aruco pipeline now infers tag width from tag family like the AprilTag pipeline - Removes unused Aruco and 200mm AprilTag models - `VisionEstimation.estimateCamPosePNP()` now requires a target model instead of assuming 16h5 - Multitarget pipeline similarly infers target model of tag family now - `PhotonPoseEstimator` can have target model set for on-rio multitarget --------- Co-authored-by: amquake <noleetarrr@gmail.com>
This commit is contained in:
@@ -41,6 +41,7 @@ import java.util.HashSet;
|
||||
import java.util.List;
|
||||
import java.util.Optional;
|
||||
import java.util.Set;
|
||||
import org.photonvision.estimation.TargetModel;
|
||||
import org.photonvision.estimation.VisionEstimation;
|
||||
import org.photonvision.targeting.PhotonPipelineResult;
|
||||
import org.photonvision.targeting.PhotonTrackedTarget;
|
||||
@@ -82,6 +83,7 @@ public class PhotonPoseEstimator {
|
||||
}
|
||||
|
||||
private AprilTagFieldLayout fieldTags;
|
||||
private TargetModel tagModel = TargetModel.kAprilTag16h5;
|
||||
private PoseStrategy primaryStrategy;
|
||||
private PoseStrategy multiTagFallbackStrategy = PoseStrategy.LOWEST_AMBIGUITY;
|
||||
private final PhotonCamera camera;
|
||||
@@ -155,6 +157,24 @@ public class PhotonPoseEstimator {
|
||||
this.fieldTags = fieldTags;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the TargetModel representing the tags being detected. This is used for on-rio multitag.
|
||||
*
|
||||
* <p>By default, this is {@link TargetModel#kAprilTag16h5}.
|
||||
*/
|
||||
public TargetModel getTagModel() {
|
||||
return tagModel;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the TargetModel representing the tags being detected. This is used for on-rio multitag.
|
||||
*
|
||||
* @param tagModel E.g. {@link TargetModel#kAprilTag16h5}.
|
||||
*/
|
||||
public void setTagModel(TargetModel tagModel) {
|
||||
this.tagModel = tagModel;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the Position Estimation Strategy being used by the Position Estimator.
|
||||
*
|
||||
@@ -419,7 +439,7 @@ public class PhotonPoseEstimator {
|
||||
|
||||
var pnpResults =
|
||||
VisionEstimation.estimateCamPosePNP(
|
||||
cameraMatrixOpt.get(), distCoeffsOpt.get(), result.getTargets(), fieldTags);
|
||||
cameraMatrixOpt.get(), distCoeffsOpt.get(), result.getTargets(), fieldTags, tagModel);
|
||||
// try fallback strategy if solvePNP fails for some reason
|
||||
if (!pnpResults.isPresent)
|
||||
return update(result, cameraMatrixOpt, distCoeffsOpt, this.multiTagFallbackStrategy);
|
||||
|
||||
Reference in New Issue
Block a user