001/* 002 * Copyright (C) Photon Vision. 003 * 004 * This program is free software: you can redistribute it and/or modify 005 * it under the terms of the GNU General Public License as published by 006 * the Free Software Foundation, either version 3 of the License, or 007 * (at your option) any later version. 008 * 009 * This program is distributed in the hope that it will be useful, 010 * but WITHOUT ANY WARRANTY; without even the implied warranty of 011 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 012 * GNU General Public License for more details. 013 * 014 * You should have received a copy of the GNU General Public License 015 * along with this program. If not, see <https://www.gnu.org/licenses/>. 016 */ 017 018package org.photonvision.vision.pipe.impl; 019 020import edu.wpi.first.apriltag.AprilTagFieldLayout; 021import java.util.ArrayList; 022import java.util.List; 023import java.util.Optional; 024import org.photonvision.common.logging.LogGroup; 025import org.photonvision.common.logging.Logger; 026import org.photonvision.estimation.TargetModel; 027import org.photonvision.estimation.VisionEstimation; 028import org.photonvision.targeting.MultiTargetPNPResult; 029import org.photonvision.vision.calibration.CameraCalibrationCoefficients; 030import org.photonvision.vision.pipe.CVPipe; 031import org.photonvision.vision.target.TrackedTarget; 032 033/** Estimate the camera pose given multiple Apriltag observations */ 034public class MultiTargetPNPPipe 035 extends CVPipe< 036 List<TrackedTarget>, 037 Optional<MultiTargetPNPResult>, 038 MultiTargetPNPPipe.MultiTargetPNPPipeParams> { 039 private static final Logger logger = new Logger(MultiTargetPNPPipe.class, LogGroup.VisionModule); 040 041 private boolean hasWarned = false; 042 043 @Override 044 protected Optional<MultiTargetPNPResult> process(List<TrackedTarget> targetList) { 045 if (params == null 046 || params.cameraCoefficients == null 047 || params.cameraCoefficients.getCameraIntrinsicsMat() == null 048 || params.cameraCoefficients.getDistCoeffsMat() == null) { 049 if (!hasWarned) { 050 logger.warn( 051 "Cannot perform solvePNP an uncalibrated camera! Please calibrate this resolution..."); 052 hasWarned = true; 053 } 054 return Optional.empty(); 055 } 056 057 return calculateCameraInField(targetList); 058 } 059 060 private Optional<MultiTargetPNPResult> calculateCameraInField(List<TrackedTarget> targetList) { 061 // Find tag IDs that exist in the tag layout 062 var tagIDsUsed = new ArrayList<Short>(); 063 for (var target : targetList) { 064 int id = target.getFiducialId(); 065 if (params.atfl.getTagPose(id).isPresent()) tagIDsUsed.add((short) id); 066 } 067 068 // Only run with multiple targets 069 if (tagIDsUsed.size() < 2) { 070 return Optional.empty(); 071 } 072 073 var estimatedPose = 074 VisionEstimation.estimateCamPosePNP( 075 params.cameraCoefficients.cameraIntrinsics.getAsWpilibMat(), 076 params.cameraCoefficients.distCoeffs.getAsWpilibMat(), 077 TrackedTarget.simpleFromTrackedTargets(targetList), 078 params.atfl, 079 params.targetModel); 080 081 if (estimatedPose.isPresent()) { 082 return Optional.of(new MultiTargetPNPResult(estimatedPose.get(), tagIDsUsed)); 083 } else { 084 return Optional.empty(); 085 } 086 } 087 088 public static class MultiTargetPNPPipeParams { 089 private final CameraCalibrationCoefficients cameraCoefficients; 090 private final AprilTagFieldLayout atfl; 091 private final TargetModel targetModel; 092 093 public MultiTargetPNPPipeParams( 094 CameraCalibrationCoefficients cameraCoefficients, 095 AprilTagFieldLayout atfl, 096 TargetModel targetModel) { 097 this.cameraCoefficients = cameraCoefficients; 098 this.atfl = atfl; 099 this.targetModel = targetModel; 100 } 101 } 102}