001/* 002 * MIT License 003 * 004 * Copyright (c) PhotonVision 005 * 006 * Permission is hereby granted, free of charge, to any person obtaining a copy 007 * of this software and associated documentation files (the "Software"), to deal 008 * in the Software without restriction, including without limitation the rights 009 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 010 * copies of the Software, and to permit persons to whom the Software is 011 * furnished to do so, subject to the following conditions: 012 * 013 * The above copyright notice and this permission notice shall be included in all 014 * copies or substantial portions of the Software. 015 * 016 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 017 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 018 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 019 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 020 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 021 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 022 * SOFTWARE. 023 */ 024 025package org.photonvision; 026 027import java.util.*; 028import org.photonvision.estimation.TargetModel; 029import org.photonvision.estimation.VisionEstimation; 030import org.photonvision.targeting.PhotonPipelineResult; 031import org.photonvision.targeting.PhotonTrackedTarget; 032import org.wpilib.driverstation.DriverStationErrors; 033import org.wpilib.hardware.hal.HAL; 034import org.wpilib.math.geometry.Pose2d; 035import org.wpilib.math.geometry.Pose3d; 036import org.wpilib.math.geometry.Rotation2d; 037import org.wpilib.math.geometry.Rotation3d; 038import org.wpilib.math.geometry.Transform3d; 039import org.wpilib.math.geometry.Translation2d; 040import org.wpilib.math.geometry.Translation3d; 041import org.wpilib.math.interpolation.TimeInterpolatableBuffer; 042import org.wpilib.math.linalg.Matrix; 043import org.wpilib.math.numbers.N1; 044import org.wpilib.math.numbers.N3; 045import org.wpilib.math.numbers.N8; 046import org.wpilib.math.util.Pair; 047import org.wpilib.vision.apriltag.AprilTagFieldLayout; 048 049/** 050 * The PhotonPoseEstimator class filters or combines readings from all the AprilTags visible at a 051 * given timestamp on the field to produce a single robot in field pose, using the strategy set 052 * below. Example usage can be found in our apriltagExample example project. 053 */ 054public class PhotonPoseEstimator { 055 private static int InstanceCount = 1; 056 057 /** Position estimation strategies that can be used by the {@link PhotonPoseEstimator} class. */ 058 public enum PoseStrategy { 059 /** Choose the Pose with the lowest ambiguity. */ 060 LOWEST_AMBIGUITY, 061 062 /** Choose the Pose which is closest to the camera height. */ 063 CLOSEST_TO_CAMERA_HEIGHT, 064 065 /** Choose the Pose which is closest to a set Reference position. */ 066 CLOSEST_TO_REFERENCE_POSE, 067 068 /** Choose the Pose which is closest to the last pose calculated */ 069 CLOSEST_TO_LAST_POSE, 070 071 /** Return the average of the best target poses using ambiguity as weight. */ 072 AVERAGE_BEST_TARGETS, 073 074 /** 075 * Use all visible tags to compute a single pose estimate on coprocessor. This option needs to 076 * be enabled on the PhotonVision web UI as well. 077 */ 078 MULTI_TAG_PNP_ON_COPROCESSOR, 079 080 /** 081 * Use all visible tags to compute a single pose estimate. This runs on the RoboRIO, and can 082 * take a lot of time. 083 */ 084 MULTI_TAG_PNP_ON_RIO, 085 086 /** 087 * Use distance data from best visible tag to compute a Pose. This runs on the RoboRIO in order 088 * to access the robot's yaw heading, and MUST have addHeadingData called every frame so heading 089 * data is up-to-date. 090 * 091 * <p>Yields a Pose2d in estimatedRobotPose (0 for z, roll, pitch) 092 * 093 * <p>https://www.chiefdelphi.com/t/frc-6328-mechanical-advantage-2025-build-thread/477314/98 094 */ 095 PNP_DISTANCE_TRIG_SOLVE, 096 097 /** 098 * Solve a constrained version of the Perspective-n-Point problem with the robot's drivebase 099 * flat on the floor. This computation takes place on the RoboRIO, and typically takes not more 100 * than 2ms. See {@link PhotonPoseEstimator.ConstrainedSolvepnpParams} and {@link 101 * org.photonvision.jni.ConstrainedSolvepnpJni} for details and tuning handles this strategy 102 * exposes. This strategy needs addHeadingData called every frame so heading data is up-to-date. 103 * If Multi-Tag PNP is enabled on the coprocessor, it will be used to provide an initial seed to 104 * the optimization algorithm -- otherwise, the multi-tag fallback strategy will be used as the 105 * seed. 106 */ 107 CONSTRAINED_SOLVEPNP 108 } 109 110 /** 111 * Tuning handles we have over the CONSTRAINED_SOLVEPNP {@link PhotonPoseEstimator.PoseStrategy}. 112 * Internally, the cost function is a sum-squared of pixel reprojection error + (optionally) 113 * heading error * heading scale factor. 114 * 115 * @param headingFree If true, heading is completely free to vary. If false, heading excursions 116 * from the provided heading measurement will be penalized 117 * @param headingScaleFactor If headingFree is false, this weights the cost of changing our robot 118 * heading estimate against the tag corner reprojection error cost. 119 */ 120 public static final record ConstrainedSolvepnpParams( 121 boolean headingFree, double headingScaleFactor) {} 122 123 private AprilTagFieldLayout fieldTags; 124 private TargetModel tagModel = TargetModel.kAprilTag36h11; 125 private Transform3d robotToCamera; 126 private final Set<Integer> reportedErrors = new HashSet<>(); 127 128 private final TimeInterpolatableBuffer<Rotation2d> headingBuffer = 129 TimeInterpolatableBuffer.createBuffer(1.0); 130 131 /** 132 * Create a new PhotonPoseEstimator. 133 * 134 * @param fieldTags A WPILib {@link AprilTagFieldLayout} linking AprilTag IDs to Pose3d objects 135 * with respect to the FIRST field using the <a href= 136 * "https://docs.wpilib.org/en/stable/docs/software/advanced-controls/geometry/coordinate-systems.html#field-coordinate-system">Field 137 * Coordinate System</a>. Note that setting the origin of this layout object will affect the 138 * results from this class. 139 * @param robotToCamera Transform3d from the center of the robot to the camera mount position (ie, 140 * robot ➔ camera) in the <a href= 141 * "https://docs.wpilib.org/en/stable/docs/software/advanced-controls/geometry/coordinate-systems.html#robot-coordinate-system">Robot 142 * Coordinate System</a>. 143 */ 144 public PhotonPoseEstimator(AprilTagFieldLayout fieldTags, Transform3d robotToCamera) { 145 this.fieldTags = fieldTags; 146 this.robotToCamera = robotToCamera; 147 148 HAL.reportUsage("PhotonVision/PhotonPoseEstimator", InstanceCount, ""); 149 InstanceCount++; 150 } 151 152 /** 153 * Get the AprilTagFieldLayout being used by the PositionEstimator. 154 * 155 * <p>Note: Setting the origin of this layout will affect the results from this class. 156 * 157 * @return the AprilTagFieldLayout 158 */ 159 public AprilTagFieldLayout getFieldTags() { 160 return fieldTags; 161 } 162 163 /** 164 * Set the AprilTagFieldLayout being used by the PositionEstimator. 165 * 166 * <p>Note: Setting the origin of this layout will affect the results from this class. 167 * 168 * @param fieldTags the AprilTagFieldLayout 169 */ 170 public void setFieldTags(AprilTagFieldLayout fieldTags) { 171 this.fieldTags = fieldTags; 172 } 173 174 /** 175 * Get the TargetModel representing the tags being detected. This is used for on-rio multitag. 176 * 177 * <p>By default, this is {@link TargetModel#kAprilTag36h11}. 178 */ 179 public TargetModel getTagModel() { 180 return tagModel; 181 } 182 183 /** 184 * Set the TargetModel representing the tags being detected. This is used for on-rio multitag. 185 * 186 * @param tagModel E.g. {@link TargetModel#kAprilTag16h5}. 187 */ 188 public void setTagModel(TargetModel tagModel) { 189 this.tagModel = tagModel; 190 } 191 192 /** 193 * Add robot heading data to buffer. Must be called periodically for the 194 * <b>PNP_DISTANCE_TRIG_SOLVE</b> strategy. 195 * 196 * @param timestampSeconds Timestamp of the robot heading data. 197 * @param heading Field-relative robot heading at given timestamp. Standard WPILIB field 198 * coordinates. 199 */ 200 public void addHeadingData(double timestampSeconds, Rotation3d heading) { 201 addHeadingData(timestampSeconds, heading.toRotation2d()); 202 } 203 204 /** 205 * Add robot heading data to buffer. Must be called periodically for the 206 * <b>PNP_DISTANCE_TRIG_SOLVE</b> strategy. 207 * 208 * @param timestampSeconds Timestamp of the robot heading data. 209 * @param heading Field-relative robot heading at given timestamp. Standard WPILIB field 210 * coordinates. 211 */ 212 public void addHeadingData(double timestampSeconds, Rotation2d heading) { 213 headingBuffer.addSample(timestampSeconds, heading); 214 } 215 216 /** 217 * Clears all heading data in the buffer, and adds a new seed. Useful for preventing estimates 218 * from utilizing heading data provided prior to a pose or rotation reset. 219 * 220 * @param timestampSeconds Timestamp of the robot heading data. 221 * @param heading Field-relative robot heading at given timestamp. Standard WPILIB field 222 * coordinates. 223 */ 224 public void resetHeadingData(double timestampSeconds, Rotation3d heading) { 225 headingBuffer.clear(); 226 addHeadingData(timestampSeconds, heading); 227 } 228 229 /** 230 * Clears all heading data in the buffer, and adds a new seed. Useful for preventing estimates 231 * from utilizing heading data provided prior to a pose or rotation reset. 232 * 233 * @param timestampSeconds Timestamp of the robot heading data. 234 * @param heading Field-relative robot heading at given timestamp. Standard WPILIB field 235 * coordinates. 236 */ 237 public void resetHeadingData(double timestampSeconds, Rotation2d heading) { 238 headingBuffer.clear(); 239 addHeadingData(timestampSeconds, heading); 240 } 241 242 /** 243 * @return The current transform from the center of the robot to the camera mount position 244 */ 245 public Transform3d getRobotToCameraTransform() { 246 return robotToCamera; 247 } 248 249 /** 250 * Useful for pan and tilt mechanisms and such. 251 * 252 * @param robotToCamera The current transform from the center of the robot to the camera mount 253 * position 254 */ 255 public void setRobotToCameraTransform(Transform3d robotToCamera) { 256 this.robotToCamera = robotToCamera; 257 } 258 259 /** 260 * @param cameraResult A pipeline result from the camera. 261 * @return Whether or not pose estimation should be performed. 262 */ 263 private boolean shouldEstimate(PhotonPipelineResult cameraResult) { 264 // Time in the past -- give up, since the following if expects times > 0 265 if (cameraResult.getTimestampSeconds() < 0) { 266 return false; 267 } 268 269 // If no targets seen, trivial case -- can't do estimation 270 return cameraResult.hasTargets(); 271 } 272 273 /** 274 * Return the estimated position of the robot by using distance data from best visible tag to 275 * compute a Pose. This runs on the RoboRIO in order to access the robot's yaw heading, and MUST 276 * have addHeadingData called every frame so heading data is up-to-date. 277 * 278 * <p>Yields a Pose2d in estimatedRobotPose (0 for z, roll, pitch) 279 * 280 * <p>https://www.chiefdelphi.com/t/frc-6328-mechanical-advantage-2025-build-thread/477314/98 281 * 282 * @param cameraResult A pipeline result from the camera. 283 * @return An {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 284 * create the estimate, or an empty optional if there's no targets or heading data. 285 */ 286 public Optional<EstimatedRobotPose> estimatePnpDistanceTrigSolvePose( 287 PhotonPipelineResult cameraResult) { 288 if (!shouldEstimate(cameraResult)) { 289 return Optional.empty(); 290 } 291 PhotonTrackedTarget bestTarget = cameraResult.getBestTarget(); 292 293 if (bestTarget == null) return Optional.empty(); 294 295 var headingSampleOpt = headingBuffer.getSample(cameraResult.getTimestampSeconds()); 296 if (headingSampleOpt.isEmpty()) { 297 return Optional.empty(); 298 } 299 Rotation2d headingSample = headingSampleOpt.get(); 300 301 Translation2d camToTagTranslation = 302 new Translation3d( 303 bestTarget.getBestCameraToTarget().getTranslation().getNorm(), 304 new Rotation3d( 305 0, 306 -Math.toRadians(bestTarget.getPitch()), 307 -Math.toRadians(bestTarget.getYaw()))) 308 .rotateBy(robotToCamera.getRotation()) 309 .toTranslation2d() 310 .rotateBy(headingSample); 311 312 var tagPoseOpt = fieldTags.getTagPose(bestTarget.getFiducialId()); 313 if (tagPoseOpt.isEmpty()) { 314 return Optional.empty(); 315 } 316 var tagPose2d = tagPoseOpt.get().toPose2d(); 317 318 Translation2d fieldToCameraTranslation = 319 tagPose2d.getTranslation().plus(camToTagTranslation.unaryMinus()); 320 321 Translation2d camToRobotTranslation = 322 robotToCamera.getTranslation().toTranslation2d().unaryMinus().rotateBy(headingSample); 323 324 Pose2d robotPose = 325 new Pose2d(fieldToCameraTranslation.plus(camToRobotTranslation), headingSample); 326 327 return Optional.of( 328 new EstimatedRobotPose( 329 new Pose3d(robotPose), 330 cameraResult.getTimestampSeconds(), 331 List.of(bestTarget), 332 PoseStrategy.PNP_DISTANCE_TRIG_SOLVE)); 333 } 334 335 /** 336 * Return the estimated position of the robot by solving a constrained version of the 337 * Perspective-n-Point problem with the robot's drivebase flat on the floor. This computation 338 * takes place on the RoboRIO, and typically takes not more than 2ms. See {@link 339 * org.photonvision.jni.ConstrainedSolvepnpJni} for tuning handles this strategy exposes. 340 * Internally, the cost function is a sum-squared of pixel reprojection error + (optionally) 341 * heading error * heading scale factor. This strategy needs addHeadingData called every frame so 342 * heading data is up-to-date. 343 * 344 * @param cameraResult A pipeline result from the camera. 345 * @param cameraMatrix Camera intrinsics from camera calibration data. 346 * @param distCoeffs Distortion coefficients from camera calibration data. 347 * @param seedPose An initial guess at robot pose, refined via optimization. Better guesses will 348 * converge faster. Can come from any pose source, but some battle-tested sources are {@link 349 * #estimateCoprocMultiTagPose(PhotonPipelineResult)}, or {@link 350 * #estimateLowestAmbiguityPose(PhotonPipelineResult)} if MultiTag results aren't available. 351 * @param headingFree If true, heading is completely free to vary. If false, heading excursions 352 * from the provided heading measurement will be penalized 353 * @param headingScaleFactor If headingFree is false, this weights the cost of changing our robot 354 * heading estimate against the tag corner reprojection error cont. 355 * @return An {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 356 * create the estimate, or an empty optional if there's no targets or heading data, or if the 357 * solver fails to solve the problem. 358 */ 359 public Optional<EstimatedRobotPose> estimateConstrainedSolvepnpPose( 360 PhotonPipelineResult cameraResult, 361 Matrix<N3, N3> cameraMatrix, 362 Matrix<N8, N1> distCoeffs, 363 Pose3d seedPose, 364 boolean headingFree, 365 double headingScaleFactor) { 366 if (!shouldEstimate(cameraResult)) { 367 return Optional.empty(); 368 } 369 // Need heading if heading fixed 370 if (!headingFree) { 371 if (headingBuffer.getSample(cameraResult.getTimestampSeconds()).isEmpty()) { 372 return Optional.empty(); 373 } else { 374 // If heading fixed, force rotation component 375 seedPose = 376 new Pose3d( 377 seedPose.getTranslation(), 378 new Rotation3d(headingBuffer.getSample(cameraResult.getTimestampSeconds()).get())); 379 } 380 } 381 var pnpResult = 382 VisionEstimation.estimateRobotPoseConstrainedSolvepnp( 383 cameraMatrix, 384 distCoeffs, 385 cameraResult.getTargets(), 386 robotToCamera, 387 seedPose, 388 fieldTags, 389 tagModel, 390 headingFree, 391 headingBuffer.getSample(cameraResult.getTimestampSeconds()).get(), 392 headingScaleFactor); 393 if (!pnpResult.isPresent()) return Optional.empty(); 394 var best = Pose3d.kZero.plus(pnpResult.get().best); // field-to-robot 395 396 return Optional.of( 397 new EstimatedRobotPose( 398 best, 399 cameraResult.getTimestampSeconds(), 400 cameraResult.getTargets(), 401 PoseStrategy.CONSTRAINED_SOLVEPNP)); 402 } 403 404 /** 405 * Return the estimated position of the robot by using all visible tags to compute a single pose 406 * estimate on coprocessor. This option needs to be enabled on the PhotonVision web UI as well. 407 * 408 * @param cameraResult A pipeline result from the camera. 409 * @return An {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 410 * create the estimate, or an empty optional if there's no targets, no multi-tag results, or 411 * multi-tag is disabled in the web UI. 412 */ 413 public Optional<EstimatedRobotPose> estimateCoprocMultiTagPose( 414 PhotonPipelineResult cameraResult) { 415 if (cameraResult.getMultiTagResult().isEmpty() || !shouldEstimate(cameraResult)) { 416 return Optional.empty(); 417 } 418 419 var best_tf = cameraResult.getMultiTagResult().get().estimatedPose.best; 420 var best = 421 Pose3d.kZero 422 .plus(best_tf) // field-to-camera 423 .relativeTo(fieldTags.getOrigin()) 424 .plus(robotToCamera.inverse()); // field-to-robot 425 return Optional.of( 426 new EstimatedRobotPose( 427 best, 428 cameraResult.getTimestampSeconds(), 429 cameraResult.getTargets(), 430 PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR)); 431 } 432 433 /** 434 * Return the estimated position of the robot by using all visible tags to compute a single pose 435 * estimate on the RoboRIO. This can take a lot of time due to the RIO's weak computing power. 436 * 437 * @param cameraResult A pipeline result from the camera. 438 * @param cameraMatrix Camera intrinsics from camera calibration data 439 * @param distCoeffs Distortion coefficients from camera calibration data. 440 * @return An {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 441 * create the estimate, or an empty optional if there's less than 2 targets visible or 442 * SolvePnP fails. 443 */ 444 public Optional<EstimatedRobotPose> estimateRioMultiTagPose( 445 PhotonPipelineResult cameraResult, Matrix<N3, N3> cameraMatrix, Matrix<N8, N1> distCoeffs) { 446 if (cameraResult.getTargets().size() < 2 || !shouldEstimate(cameraResult)) { 447 return Optional.empty(); 448 } 449 450 var pnpResult = 451 VisionEstimation.estimateCamPosePNP( 452 cameraMatrix, distCoeffs, cameraResult.getTargets(), fieldTags, tagModel); 453 if (!pnpResult.isPresent()) return Optional.empty(); 454 455 var best = 456 Pose3d.kZero 457 .plus(pnpResult.get().best) // field-to-camera 458 .plus(robotToCamera.inverse()); // field-to-robot 459 460 return Optional.of( 461 new EstimatedRobotPose( 462 best, 463 cameraResult.getTimestampSeconds(), 464 cameraResult.getTargets(), 465 PoseStrategy.MULTI_TAG_PNP_ON_RIO)); 466 } 467 468 /** 469 * Return the estimated position of the robot with the lowest position ambiguity from a pipeline 470 * result. 471 * 472 * @param cameraResult A pipeline result from the camera. 473 * @return An {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 474 * create the estimate, or an empty optional if there's no targets. 475 */ 476 public Optional<EstimatedRobotPose> estimateLowestAmbiguityPose( 477 PhotonPipelineResult cameraResult) { 478 if (!shouldEstimate(cameraResult)) { 479 return Optional.empty(); 480 } 481 PhotonTrackedTarget lowestAmbiguityTarget = null; 482 483 double lowestAmbiguityScore = 10; 484 485 for (PhotonTrackedTarget target : cameraResult.targets) { 486 double targetPoseAmbiguity = target.getPoseAmbiguity(); 487 // Make sure the target is a Fiducial target. 488 if (targetPoseAmbiguity != -1 && targetPoseAmbiguity < lowestAmbiguityScore) { 489 lowestAmbiguityScore = targetPoseAmbiguity; 490 lowestAmbiguityTarget = target; 491 } 492 } 493 494 // Although there are confirmed to be targets, none of them may be fiducial 495 // targets. 496 if (lowestAmbiguityTarget == null) return Optional.empty(); 497 498 int targetFiducialId = lowestAmbiguityTarget.getFiducialId(); 499 500 Optional<Pose3d> targetPosition = fieldTags.getTagPose(targetFiducialId); 501 502 if (targetPosition.isEmpty()) { 503 reportFiducialPoseError(targetFiducialId); 504 return Optional.empty(); 505 } 506 507 return Optional.of( 508 new EstimatedRobotPose( 509 targetPosition 510 .get() 511 .transformBy(lowestAmbiguityTarget.getBestCameraToTarget().inverse()) 512 .transformBy(robotToCamera.inverse()), 513 cameraResult.getTimestampSeconds(), 514 List.of(lowestAmbiguityTarget), 515 PoseStrategy.LOWEST_AMBIGUITY)); 516 } 517 518 /** 519 * Return the estimated position of the robot using the target with the lowest delta height 520 * difference between the estimated and actual height of the camera. 521 * 522 * @param cameraResult A pipeline result from the camera. 523 * @return An {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 524 * create the estimate, or an empty optional if there's no targets. 525 */ 526 public Optional<EstimatedRobotPose> estimateClosestToCameraHeightPose( 527 PhotonPipelineResult cameraResult) { 528 if (!shouldEstimate(cameraResult)) { 529 return Optional.empty(); 530 } 531 double smallestHeightDifference = 10e9; 532 Pose3d bestPose = null; 533 PhotonTrackedTarget bestTarget = null; 534 535 for (PhotonTrackedTarget target : cameraResult.targets) { 536 int targetFiducialId = target.getFiducialId(); 537 538 // Don't report errors for non-fiducial targets. This could also be resolved by 539 // adding -1 to 540 // the initial HashSet. 541 if (targetFiducialId == -1) continue; 542 543 Optional<Pose3d> targetPosition = fieldTags.getTagPose(target.getFiducialId()); 544 545 if (targetPosition.isEmpty()) { 546 reportFiducialPoseError(target.getFiducialId()); 547 continue; 548 } 549 550 double alternateTransformDelta = 551 Math.abs( 552 robotToCamera.getZ() 553 - targetPosition 554 .get() 555 .transformBy(target.getAlternateCameraToTarget().inverse()) 556 .getZ()); 557 double bestTransformDelta = 558 Math.abs( 559 robotToCamera.getZ() 560 - targetPosition 561 .get() 562 .transformBy(target.getBestCameraToTarget().inverse()) 563 .getZ()); 564 565 if (alternateTransformDelta < smallestHeightDifference) { 566 smallestHeightDifference = alternateTransformDelta; 567 bestPose = 568 targetPosition 569 .get() 570 .transformBy(target.getAlternateCameraToTarget().inverse()) 571 .transformBy(robotToCamera.inverse()); 572 bestTarget = target; 573 } 574 575 if (bestTransformDelta < smallestHeightDifference) { 576 smallestHeightDifference = bestTransformDelta; 577 bestPose = 578 targetPosition 579 .get() 580 .transformBy(target.getBestCameraToTarget().inverse()) 581 .transformBy(robotToCamera.inverse()); 582 bestTarget = target; 583 } 584 } 585 586 // Need to null check here in case none of the provided targets are fiducial. 587 if (bestTarget == null) return Optional.empty(); 588 return Optional.of( 589 new EstimatedRobotPose( 590 bestPose, 591 cameraResult.getTimestampSeconds(), 592 List.of(bestTarget), 593 PoseStrategy.CLOSEST_TO_CAMERA_HEIGHT)); 594 } 595 596 /** 597 * Return the estimated position of the robot using the target with the lowest delta in the vector 598 * magnitude between it and the reference pose. 599 * 600 * @param cameraResult A pipeline result from the camera. 601 * @param referencePose reference pose to check vector magnitude difference against. 602 * @return An {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 603 * create the estimate, or an empty optional if there's no targets. 604 */ 605 public Optional<EstimatedRobotPose> estimateClosestToReferencePose( 606 PhotonPipelineResult cameraResult, Pose3d referencePose) { 607 if (!shouldEstimate(cameraResult)) { 608 return Optional.empty(); 609 } 610 if (referencePose == null) { 611 DriverStationErrors.reportError( 612 "[PhotonPoseEstimator] Tried to use reference pose strategy without setting the reference!", 613 false); 614 return Optional.empty(); 615 } 616 617 double smallestPoseDelta = 10e9; 618 Pose3d lowestDeltaPose = null; 619 PhotonTrackedTarget lowestDeltaTarget = null; 620 621 for (PhotonTrackedTarget target : cameraResult.targets) { 622 int targetFiducialId = target.getFiducialId(); 623 624 // Don't report errors for non-fiducial targets. This could also be resolved by 625 // adding -1 to 626 // the initial HashSet. 627 if (targetFiducialId == -1) continue; 628 629 Optional<Pose3d> targetPosition = fieldTags.getTagPose(target.getFiducialId()); 630 631 if (targetPosition.isEmpty()) { 632 reportFiducialPoseError(targetFiducialId); 633 continue; 634 } 635 636 Pose3d altTransformPosition = 637 targetPosition 638 .get() 639 .transformBy(target.getAlternateCameraToTarget().inverse()) 640 .transformBy(robotToCamera.inverse()); 641 Pose3d bestTransformPosition = 642 targetPosition 643 .get() 644 .transformBy(target.getBestCameraToTarget().inverse()) 645 .transformBy(robotToCamera.inverse()); 646 647 double altDifference = Math.abs(calculateDifference(referencePose, altTransformPosition)); 648 double bestDifference = Math.abs(calculateDifference(referencePose, bestTransformPosition)); 649 650 if (altDifference < smallestPoseDelta) { 651 smallestPoseDelta = altDifference; 652 lowestDeltaPose = altTransformPosition; 653 lowestDeltaTarget = target; 654 } 655 if (bestDifference < smallestPoseDelta) { 656 smallestPoseDelta = bestDifference; 657 lowestDeltaPose = bestTransformPosition; 658 lowestDeltaTarget = target; 659 } 660 } 661 if (lowestDeltaTarget == null) return Optional.empty(); 662 return Optional.of( 663 new EstimatedRobotPose( 664 lowestDeltaPose, 665 cameraResult.getTimestampSeconds(), 666 List.of(lowestDeltaTarget), 667 PoseStrategy.CLOSEST_TO_REFERENCE_POSE)); 668 } 669 670 /** 671 * Return the average of the best target poses using ambiguity as weight. 672 * 673 * @param cameraResult A pipeline result from the camera. 674 * @return An {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 675 * create the estimate, or an empty optional if there's no targets. 676 */ 677 public Optional<EstimatedRobotPose> estimateAverageBestTargetsPose( 678 PhotonPipelineResult cameraResult) { 679 if (!shouldEstimate(cameraResult)) { 680 return Optional.empty(); 681 } 682 List<Pair<PhotonTrackedTarget, Pose3d>> estimatedRobotPoses = new ArrayList<>(); 683 double totalAmbiguity = 0; 684 685 for (PhotonTrackedTarget target : cameraResult.targets) { 686 int targetFiducialId = target.getFiducialId(); 687 688 // Don't report errors for non-fiducial targets. This could also be resolved by 689 // adding -1 to 690 // the initial HashSet. 691 if (targetFiducialId == -1) continue; 692 693 Optional<Pose3d> targetPosition = fieldTags.getTagPose(target.getFiducialId()); 694 695 if (targetPosition.isEmpty()) { 696 reportFiducialPoseError(targetFiducialId); 697 continue; 698 } 699 700 double targetPoseAmbiguity = target.getPoseAmbiguity(); 701 702 // Pose ambiguity is 0, use that pose 703 if (targetPoseAmbiguity == 0) { 704 return Optional.of( 705 new EstimatedRobotPose( 706 targetPosition 707 .get() 708 .transformBy(target.getBestCameraToTarget().inverse()) 709 .transformBy(robotToCamera.inverse()), 710 cameraResult.getTimestampSeconds(), 711 List.of(target), 712 PoseStrategy.AVERAGE_BEST_TARGETS)); 713 } 714 715 totalAmbiguity += 1.0 / target.getPoseAmbiguity(); 716 717 estimatedRobotPoses.add( 718 new Pair<>( 719 target, 720 targetPosition 721 .get() 722 .transformBy(target.getBestCameraToTarget().inverse()) 723 .transformBy(robotToCamera.inverse()))); 724 } 725 726 // Take the average 727 728 Translation3d transform = new Translation3d(); 729 Rotation3d rotation = new Rotation3d(); 730 731 if (estimatedRobotPoses.isEmpty()) return Optional.empty(); 732 733 List<PhotonTrackedTarget> usedTargets = new ArrayList<>(estimatedRobotPoses.size()); 734 for (Pair<PhotonTrackedTarget, Pose3d> pair : estimatedRobotPoses) { 735 // Total ambiguity is non-zero confirmed because if it was zero, that pose was 736 // returned. 737 double weight = (1.0 / pair.getFirst().getPoseAmbiguity()) / totalAmbiguity; 738 Pose3d estimatedPose = pair.getSecond(); 739 transform = transform.plus(estimatedPose.getTranslation().times(weight)); 740 rotation = rotation.rotateBy(estimatedPose.getRotation().times(weight)); 741 usedTargets.add(pair.getFirst()); 742 } 743 744 return Optional.of( 745 new EstimatedRobotPose( 746 new Pose3d(transform, rotation), 747 cameraResult.getTimestampSeconds(), 748 usedTargets, 749 PoseStrategy.AVERAGE_BEST_TARGETS)); 750 } 751 752 /** 753 * Difference is defined as the vector magnitude between the two poses 754 * 755 * @return The absolute "difference" (>=0) between two Pose3ds. 756 */ 757 private double calculateDifference(Pose3d x, Pose3d y) { 758 return x.getTranslation().getDistance(y.getTranslation()); 759 } 760 761 private void reportFiducialPoseError(int fiducialId) { 762 if (!reportedErrors.contains(fiducialId)) { 763 DriverStationErrors.reportError( 764 "[PhotonPoseEstimator] Tried to get pose of unknown AprilTag: " + fiducialId, false); 765 reportedErrors.add(fiducialId); 766 } 767 } 768}