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 edu.wpi.first.apriltag.AprilTagFieldLayout; 028import edu.wpi.first.cscore.OpenCvLoader; 029import edu.wpi.first.hal.FRCNetComm.tResourceType; 030import edu.wpi.first.hal.HAL; 031import edu.wpi.first.math.Matrix; 032import edu.wpi.first.math.Pair; 033import edu.wpi.first.math.geometry.Pose2d; 034import edu.wpi.first.math.geometry.Pose3d; 035import edu.wpi.first.math.geometry.Rotation2d; 036import edu.wpi.first.math.geometry.Rotation3d; 037import edu.wpi.first.math.geometry.Transform3d; 038import edu.wpi.first.math.geometry.Translation2d; 039import edu.wpi.first.math.geometry.Translation3d; 040import edu.wpi.first.math.interpolation.TimeInterpolatableBuffer; 041import edu.wpi.first.math.numbers.N1; 042import edu.wpi.first.math.numbers.N3; 043import edu.wpi.first.math.numbers.N8; 044import edu.wpi.first.wpilibj.DriverStation; 045import java.util.ArrayList; 046import java.util.HashSet; 047import java.util.List; 048import java.util.Optional; 049import java.util.Set; 050import org.photonvision.estimation.TargetModel; 051import org.photonvision.estimation.VisionEstimation; 052import org.photonvision.targeting.PhotonPipelineResult; 053import org.photonvision.targeting.PhotonTrackedTarget; 054 055/** 056 * The PhotonPoseEstimator class filters or combines readings from all the AprilTags visible at a 057 * given timestamp on the field to produce a single robot in field pose, using the strategy set 058 * below. Example usage can be found in our apriltagExample example project. 059 */ 060public class PhotonPoseEstimator { 061 private static int InstanceCount = 0; 062 063 /** Position estimation strategies that can be used by the {@link PhotonPoseEstimator} class. */ 064 public enum PoseStrategy { 065 /** Choose the Pose with the lowest ambiguity. */ 066 LOWEST_AMBIGUITY, 067 068 /** Choose the Pose which is closest to the camera height. */ 069 CLOSEST_TO_CAMERA_HEIGHT, 070 071 /** Choose the Pose which is closest to a set Reference position. */ 072 CLOSEST_TO_REFERENCE_POSE, 073 074 /** Choose the Pose which is closest to the last pose calculated */ 075 CLOSEST_TO_LAST_POSE, 076 077 /** Return the average of the best target poses using ambiguity as weight. */ 078 AVERAGE_BEST_TARGETS, 079 080 /** 081 * Use all visible tags to compute a single pose estimate on coprocessor. This option needs to 082 * be enabled on the PhotonVision web UI as well. 083 */ 084 MULTI_TAG_PNP_ON_COPROCESSOR, 085 086 /** 087 * Use all visible tags to compute a single pose estimate. This runs on the RoboRIO, and can 088 * take a lot of time. 089 */ 090 MULTI_TAG_PNP_ON_RIO, 091 092 /** 093 * Use distance data from best visible tag to compute a Pose. This runs on the RoboRIO in order 094 * to access the robot's yaw heading, and MUST have addHeadingData called every frame so heading 095 * data is up-to-date. 096 * 097 * <p>Yields a Pose2d in estimatedRobotPose (0 for z, roll, pitch) 098 * 099 * <p>https://www.chiefdelphi.com/t/frc-6328-mechanical-advantage-2025-build-thread/477314/98 100 */ 101 PNP_DISTANCE_TRIG_SOLVE, 102 103 /** 104 * Solve a constrained version of the Perspective-n-Point problem with the robot's drivebase 105 * flat on the floor. This computation takes place on the RoboRIO, and typically takes not more 106 * than 2ms. See {@link PhotonPoseEstimator.ConstrainedSolvepnpParams} and {@link 107 * org.photonvision.jni.ConstrainedSolvepnpJni} for details and tuning handles this strategy 108 * exposes. This strategy needs addHeadingData called every frame so heading data is up-to-date. 109 * If Multi-Tag PNP is enabled on the coprocessor, it will be used to provide an initial seed to 110 * the optimization algorithm -- otherwise, the multi-tag fallback strategy will be used as the 111 * seed. 112 */ 113 CONSTRAINED_SOLVEPNP 114 } 115 116 /** 117 * Tuning handles we have over the CONSTRAINED_SOLVEPNP {@link PhotonPoseEstimator.PoseStrategy}. 118 * Internally, the cost function is a sum-squared of pixel reprojection error + (optionally) 119 * heading error * heading scale factor. 120 * 121 * @param headingFree If true, heading is completely free to vary. If false, heading excursions 122 * from the provided heading measurement will be penalized 123 * @param headingScaleFactor If headingFree is false, this weights the cost of changing our robot 124 * heading estimate against the tag corner reprojection error const. 125 */ 126 public static final record ConstrainedSolvepnpParams( 127 boolean headingFree, double headingScaleFactor) {} 128 129 private AprilTagFieldLayout fieldTags; 130 private TargetModel tagModel = TargetModel.kAprilTag36h11; 131 private PoseStrategy primaryStrategy; 132 private PoseStrategy multiTagFallbackStrategy = PoseStrategy.LOWEST_AMBIGUITY; 133 private Transform3d robotToCamera; 134 135 private Pose3d lastPose; 136 private Pose3d referencePose; 137 protected double poseCacheTimestampSeconds = -1; 138 private final Set<Integer> reportedErrors = new HashSet<>(); 139 140 private final TimeInterpolatableBuffer<Rotation2d> headingBuffer = 141 TimeInterpolatableBuffer.createBuffer(1.0); 142 143 /** 144 * Create a new PhotonPoseEstimator. 145 * 146 * @param fieldTags A WPILib {@link AprilTagFieldLayout} linking AprilTag IDs to Pose3d objects 147 * with respect to the FIRST field using the <a href= 148 * "https://docs.wpilib.org/en/stable/docs/software/advanced-controls/geometry/coordinate-systems.html#field-coordinate-system">Field 149 * Coordinate System</a>. Note that setting the origin of this layout object will affect the 150 * results from this class. 151 * @param strategy The strategy it should use to determine the best pose. 152 * @param robotToCamera Transform3d from the center of the robot to the camera mount position (ie, 153 * robot ➔ camera) in the <a href= 154 * "https://docs.wpilib.org/en/stable/docs/software/advanced-controls/geometry/coordinate-systems.html#robot-coordinate-system">Robot 155 * Coordinate System</a>. 156 */ 157 public PhotonPoseEstimator( 158 AprilTagFieldLayout fieldTags, PoseStrategy strategy, Transform3d robotToCamera) { 159 this.fieldTags = fieldTags; 160 this.primaryStrategy = strategy; 161 this.robotToCamera = robotToCamera; 162 163 if (strategy == PoseStrategy.MULTI_TAG_PNP_ON_RIO 164 || strategy == PoseStrategy.CONSTRAINED_SOLVEPNP) { 165 OpenCvLoader.forceStaticLoad(); 166 } 167 168 HAL.report(tResourceType.kResourceType_PhotonPoseEstimator, InstanceCount); 169 InstanceCount++; 170 } 171 172 /** Invalidates the pose cache. */ 173 private void invalidatePoseCache() { 174 poseCacheTimestampSeconds = -1; 175 } 176 177 private void checkUpdate(Object oldObj, Object newObj) { 178 if (oldObj != newObj && oldObj != null && !oldObj.equals(newObj)) { 179 invalidatePoseCache(); 180 } 181 } 182 183 /** 184 * Get the AprilTagFieldLayout being used by the PositionEstimator. 185 * 186 * <p>Note: Setting the origin of this layout will affect the results from this class. 187 * 188 * @return the AprilTagFieldLayout 189 */ 190 public AprilTagFieldLayout getFieldTags() { 191 return fieldTags; 192 } 193 194 /** 195 * Set the AprilTagFieldLayout being used by the PositionEstimator. 196 * 197 * <p>Note: Setting the origin of this layout will affect the results from this class. 198 * 199 * @param fieldTags the AprilTagFieldLayout 200 */ 201 public void setFieldTags(AprilTagFieldLayout fieldTags) { 202 checkUpdate(this.fieldTags, fieldTags); 203 this.fieldTags = fieldTags; 204 } 205 206 /** 207 * Get the TargetModel representing the tags being detected. This is used for on-rio multitag. 208 * 209 * <p>By default, this is {@link TargetModel#kAprilTag36h11}. 210 */ 211 public TargetModel getTagModel() { 212 return tagModel; 213 } 214 215 /** 216 * Set the TargetModel representing the tags being detected. This is used for on-rio multitag. 217 * 218 * @param tagModel E.g. {@link TargetModel#kAprilTag16h5}. 219 */ 220 public void setTagModel(TargetModel tagModel) { 221 this.tagModel = tagModel; 222 } 223 224 /** 225 * Get the Position Estimation Strategy being used by the Position Estimator. 226 * 227 * @return the strategy 228 */ 229 public PoseStrategy getPrimaryStrategy() { 230 return primaryStrategy; 231 } 232 233 /** 234 * Set the Position Estimation Strategy used by the Position Estimator. 235 * 236 * @param strategy the strategy to set 237 */ 238 public void setPrimaryStrategy(PoseStrategy strategy) { 239 checkUpdate(this.primaryStrategy, strategy); 240 241 if (strategy == PoseStrategy.MULTI_TAG_PNP_ON_RIO 242 || strategy == PoseStrategy.CONSTRAINED_SOLVEPNP) { 243 OpenCvLoader.forceStaticLoad(); 244 } 245 this.primaryStrategy = strategy; 246 } 247 248 /** 249 * Set the Position Estimation Strategy used in multi-tag mode when only one tag can be seen. Must 250 * NOT be MULTI_TAG_PNP 251 * 252 * @param strategy the strategy to set 253 */ 254 public void setMultiTagFallbackStrategy(PoseStrategy strategy) { 255 checkUpdate(this.multiTagFallbackStrategy, strategy); 256 if (strategy == PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR 257 || strategy == PoseStrategy.MULTI_TAG_PNP_ON_RIO) { 258 DriverStation.reportWarning( 259 "Fallback cannot be set to MULTI_TAG_PNP! Setting to lowest ambiguity", false); 260 strategy = PoseStrategy.LOWEST_AMBIGUITY; 261 } 262 this.multiTagFallbackStrategy = strategy; 263 } 264 265 /** 266 * Return the reference position that is being used by the estimator. 267 * 268 * @return the referencePose 269 */ 270 public Pose3d getReferencePose() { 271 return referencePose; 272 } 273 274 /** 275 * Update the stored reference pose for use when using the <b>CLOSEST_TO_REFERENCE_POSE</b> 276 * strategy. 277 * 278 * @param referencePose the referencePose to set 279 */ 280 public void setReferencePose(Pose3d referencePose) { 281 checkUpdate(this.referencePose, referencePose); 282 this.referencePose = referencePose; 283 } 284 285 /** 286 * Update the stored reference pose for use when using the <b>CLOSEST_TO_REFERENCE_POSE</b> 287 * strategy. 288 * 289 * @param referencePose the referencePose to set 290 */ 291 public void setReferencePose(Pose2d referencePose) { 292 setReferencePose(new Pose3d(referencePose)); 293 } 294 295 /** 296 * Update the stored last pose. Useful for setting the initial estimate when using the 297 * <b>CLOSEST_TO_LAST_POSE</b> strategy. 298 * 299 * @param lastPose the lastPose to set 300 */ 301 public void setLastPose(Pose3d lastPose) { 302 this.lastPose = lastPose; 303 } 304 305 /** 306 * Update the stored last pose. Useful for setting the initial estimate when using the 307 * <b>CLOSEST_TO_LAST_POSE</b> strategy. 308 * 309 * @param lastPose the lastPose to set 310 */ 311 public void setLastPose(Pose2d lastPose) { 312 setLastPose(new Pose3d(lastPose)); 313 } 314 315 /** 316 * Add robot heading data to buffer. Must be called periodically for the 317 * <b>PNP_DISTANCE_TRIG_SOLVE</b> strategy. 318 * 319 * @param timestampSeconds timestamp of the robot heading data. 320 * @param heading Field-relative robot heading at given timestamp. Standard WPILIB field 321 * coordinates. 322 */ 323 public void addHeadingData(double timestampSeconds, Rotation3d heading) { 324 addHeadingData(timestampSeconds, heading.toRotation2d()); 325 } 326 327 /** 328 * Add robot heading data to buffer. Must be called periodically for the 329 * <b>PNP_DISTANCE_TRIG_SOLVE</b> strategy. 330 * 331 * @param timestampSeconds timestamp of the robot heading data. 332 * @param heading Field-relative robot heading at given timestamp. Standard WPILIB field 333 * coordinates. 334 */ 335 public void addHeadingData(double timestampSeconds, Rotation2d heading) { 336 headingBuffer.addSample(timestampSeconds, heading); 337 } 338 339 /** 340 * Clears all heading data in the buffer, and adds a new seed. Useful for preventing estimates 341 * from utilizing heading data provided prior to a pose or rotation reset. 342 * 343 * @param timestampSeconds timestamp of the robot heading data. 344 * @param heading Field-relative robot heading at given timestamp. Standard WPILIB field 345 * coordinates. 346 */ 347 public void resetHeadingData(double timestampSeconds, Rotation2d heading) { 348 headingBuffer.clear(); 349 addHeadingData(timestampSeconds, heading); 350 } 351 352 /** 353 * @return The current transform from the center of the robot to the camera mount position 354 */ 355 public Transform3d getRobotToCameraTransform() { 356 return robotToCamera; 357 } 358 359 /** 360 * Useful for pan and tilt mechanisms and such. 361 * 362 * @param robotToCamera The current transform from the center of the robot to the camera mount 363 * position 364 */ 365 public void setRobotToCameraTransform(Transform3d robotToCamera) { 366 this.robotToCamera = robotToCamera; 367 } 368 369 /** 370 * Updates the estimated position of the robot, assuming no camera calibration is required for the 371 * selected strategy. Returns empty if: 372 * 373 * <ul> 374 * <li>The timestamp of the provided pipeline result is the same as in the previous call to 375 * {@code update()}. 376 * <li>No targets were found in the pipeline results. 377 * </ul> 378 * 379 * Will report a warning if strategy is multi-tag-on-rio because camera calibration data is not 380 * provided in this overload. 381 * 382 * @param cameraResult The latest pipeline result from the camera 383 * @return an {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 384 * create the estimate. 385 */ 386 public Optional<EstimatedRobotPose> update(PhotonPipelineResult cameraResult) { 387 return update(cameraResult, Optional.empty(), Optional.empty()); 388 } 389 390 /** 391 * Updates the estimated position of the robot. Returns empty if: 392 * 393 * <ul> 394 * <li>The timestamp of the provided pipeline result is the same as in the previous call to 395 * {@code update()}. 396 * <li>No targets were found in the pipeline results. 397 * <li>The strategy is CONSTRAINED_SOLVEPNP, but no constrainedPnpParams were provided (use the 398 * other function overload). 399 * </ul> 400 * 401 * @param cameraMatrix Camera calibration data for multi-tag-on-rio strategy - can be empty 402 * otherwise 403 * @param distCoeffs Camera calibration data for multi-tag-on-rio strategy - can be empty 404 * otherwise 405 * @return an {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 406 * create the estimate. 407 */ 408 public Optional<EstimatedRobotPose> update( 409 PhotonPipelineResult cameraResult, 410 Optional<Matrix<N3, N3>> cameraMatrix, 411 Optional<Matrix<N8, N1>> distCoeffs) { 412 return update(cameraResult, cameraMatrix, distCoeffs, Optional.empty()); 413 } 414 415 /** 416 * Updates the estimated position of the robot. Returns empty if: 417 * 418 * <ul> 419 * <li>The timestamp of the provided pipeline result is the same as in the previous call to 420 * {@code update()}. 421 * <li>No targets were found in the pipeline results. 422 * <li>The strategy is CONSTRAINED_SOLVEPNP, but the provided constrainedPnpParams are empty. 423 * </ul> 424 * 425 * @param cameraMatrix Camera calibration data for multi-tag-on-rio strategy - can be empty 426 * otherwise 427 * @param distCoeffs Camera calibration data for multi-tag-on-rio strategy - can be empty 428 * otherwise 429 * @param constrainedPnpParams Constrained SolvePNP params, if needed. 430 * @return an {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 431 * create the estimate. 432 */ 433 public Optional<EstimatedRobotPose> update( 434 PhotonPipelineResult cameraResult, 435 Optional<Matrix<N3, N3>> cameraMatrix, 436 Optional<Matrix<N8, N1>> distCoeffs, 437 Optional<ConstrainedSolvepnpParams> constrainedPnpParams) { 438 // Time in the past -- give up, since the following if expects times > 0 439 if (cameraResult.getTimestampSeconds() < 0) { 440 return Optional.empty(); 441 } 442 443 // If the pose cache timestamp was set, and the result is from the same 444 // timestamp, return an 445 // empty result 446 if (poseCacheTimestampSeconds > 0 447 && Math.abs(poseCacheTimestampSeconds - cameraResult.getTimestampSeconds()) < 1e-6) { 448 return Optional.empty(); 449 } 450 451 // Remember the timestamp of the current result used 452 poseCacheTimestampSeconds = cameraResult.getTimestampSeconds(); 453 454 // If no targets seen, trivial case -- return empty result 455 if (!cameraResult.hasTargets()) { 456 return Optional.empty(); 457 } 458 459 return update( 460 cameraResult, cameraMatrix, distCoeffs, constrainedPnpParams, this.primaryStrategy); 461 } 462 463 /** 464 * Internal convenience method for using a fallback strategy for update(). This should only be 465 * called after timestamp checks have been done by another update() overload. 466 * 467 * @param cameraResult The latest pipeline result from the camera 468 * @param strategy The pose strategy to use. Can't be CONSTRAINED_SOLVEPNP. 469 * @return an {@link EstimatedRobotPose} with an estimated pose, timestamp, and targets used to 470 * create the estimate. 471 */ 472 private Optional<EstimatedRobotPose> update( 473 PhotonPipelineResult cameraResult, PoseStrategy strategy) { 474 return update(cameraResult, Optional.empty(), Optional.empty(), Optional.empty(), strategy); 475 } 476 477 private Optional<EstimatedRobotPose> update( 478 PhotonPipelineResult cameraResult, 479 Optional<Matrix<N3, N3>> cameraMatrix, 480 Optional<Matrix<N8, N1>> distCoeffs, 481 Optional<ConstrainedSolvepnpParams> constrainedPnpParams, 482 PoseStrategy strategy) { 483 Optional<EstimatedRobotPose> estimatedPose = 484 switch (strategy) { 485 case LOWEST_AMBIGUITY -> lowestAmbiguityStrategy(cameraResult); 486 case CLOSEST_TO_CAMERA_HEIGHT -> closestToCameraHeightStrategy(cameraResult); 487 case CLOSEST_TO_REFERENCE_POSE -> 488 closestToReferencePoseStrategy(cameraResult, referencePose); 489 case CLOSEST_TO_LAST_POSE -> { 490 setReferencePose(lastPose); 491 yield closestToReferencePoseStrategy(cameraResult, referencePose); 492 } 493 case AVERAGE_BEST_TARGETS -> averageBestTargetsStrategy(cameraResult); 494 case MULTI_TAG_PNP_ON_RIO -> 495 multiTagOnRioStrategy(cameraResult, cameraMatrix, distCoeffs); 496 case MULTI_TAG_PNP_ON_COPROCESSOR -> multiTagOnCoprocStrategy(cameraResult); 497 case PNP_DISTANCE_TRIG_SOLVE -> pnpDistanceTrigSolveStrategy(cameraResult); 498 case CONSTRAINED_SOLVEPNP -> 499 constrainedPnpStrategy(cameraResult, cameraMatrix, distCoeffs, constrainedPnpParams); 500 }; 501 502 if (estimatedPose.isPresent()) { 503 lastPose = estimatedPose.get().estimatedPose; 504 } 505 506 return estimatedPose; 507 } 508 509 private Optional<EstimatedRobotPose> pnpDistanceTrigSolveStrategy(PhotonPipelineResult result) { 510 PhotonTrackedTarget bestTarget = result.getBestTarget(); 511 512 if (bestTarget == null) return Optional.empty(); 513 514 var headingSampleOpt = headingBuffer.getSample(result.getTimestampSeconds()); 515 if (headingSampleOpt.isEmpty()) { 516 return Optional.empty(); 517 } 518 Rotation2d headingSample = headingSampleOpt.get(); 519 520 Translation2d camToTagTranslation = 521 new Translation3d( 522 bestTarget.getBestCameraToTarget().getTranslation().getNorm(), 523 new Rotation3d( 524 0, 525 -Math.toRadians(bestTarget.getPitch()), 526 -Math.toRadians(bestTarget.getYaw()))) 527 .rotateBy(robotToCamera.getRotation()) 528 .toTranslation2d() 529 .rotateBy(headingSample); 530 531 var tagPoseOpt = fieldTags.getTagPose(bestTarget.getFiducialId()); 532 if (tagPoseOpt.isEmpty()) { 533 return Optional.empty(); 534 } 535 var tagPose2d = tagPoseOpt.get().toPose2d(); 536 537 Translation2d fieldToCameraTranslation = 538 tagPose2d.getTranslation().plus(camToTagTranslation.unaryMinus()); 539 540 Translation2d camToRobotTranslation = 541 robotToCamera.getTranslation().toTranslation2d().unaryMinus().rotateBy(headingSample); 542 543 Pose2d robotPose = 544 new Pose2d(fieldToCameraTranslation.plus(camToRobotTranslation), headingSample); 545 546 return Optional.of( 547 new EstimatedRobotPose( 548 new Pose3d(robotPose), 549 result.getTimestampSeconds(), 550 result.getTargets(), 551 PoseStrategy.PNP_DISTANCE_TRIG_SOLVE)); 552 } 553 554 private Optional<EstimatedRobotPose> constrainedPnpStrategy( 555 PhotonPipelineResult result, 556 Optional<Matrix<N3, N3>> cameraMatrixOpt, 557 Optional<Matrix<N8, N1>> distCoeffsOpt, 558 Optional<ConstrainedSolvepnpParams> constrainedPnpParams) { 559 boolean hasCalibData = cameraMatrixOpt.isPresent() && distCoeffsOpt.isPresent(); 560 // cannot run multitagPNP, use fallback strategy 561 if (!hasCalibData) { 562 return update( 563 result, cameraMatrixOpt, distCoeffsOpt, Optional.empty(), this.multiTagFallbackStrategy); 564 } 565 566 if (constrainedPnpParams.isEmpty()) { 567 return Optional.empty(); 568 } 569 570 // Need heading if heading fixed 571 if (!constrainedPnpParams.get().headingFree 572 && headingBuffer.getSample(result.getTimestampSeconds()).isEmpty()) { 573 return update( 574 result, cameraMatrixOpt, distCoeffsOpt, Optional.empty(), this.multiTagFallbackStrategy); 575 } 576 577 Pose3d fieldToRobotSeed; 578 579 // Attempt to use multi-tag to get a pose estimate seed 580 if (result.getMultiTagResult().isPresent()) { 581 fieldToRobotSeed = 582 Pose3d.kZero.plus( 583 result.getMultiTagResult().get().estimatedPose.best.plus(robotToCamera.inverse())); 584 } else { 585 // HACK - use fallback strategy to gimme a seed pose 586 // TODO - make sure nested update doesn't break state 587 var nestedUpdate = 588 update( 589 result, 590 cameraMatrixOpt, 591 distCoeffsOpt, 592 Optional.empty(), 593 this.multiTagFallbackStrategy); 594 if (nestedUpdate.isEmpty()) { 595 // best i can do is bail 596 return Optional.empty(); 597 } 598 fieldToRobotSeed = nestedUpdate.get().estimatedPose; 599 } 600 601 if (!constrainedPnpParams.get().headingFree) { 602 // If heading fixed, force rotation component 603 fieldToRobotSeed = 604 new Pose3d( 605 fieldToRobotSeed.getTranslation(), 606 new Rotation3d(headingBuffer.getSample(result.getTimestampSeconds()).get())); 607 } 608 609 var pnpResult = 610 VisionEstimation.estimateRobotPoseConstrainedSolvepnp( 611 cameraMatrixOpt.get(), 612 distCoeffsOpt.get(), 613 result.getTargets(), 614 robotToCamera, 615 fieldToRobotSeed, 616 fieldTags, 617 tagModel, 618 constrainedPnpParams.get().headingFree, 619 headingBuffer.getSample(result.getTimestampSeconds()).get(), 620 constrainedPnpParams.get().headingScaleFactor); 621 // try fallback strategy if solvePNP fails for some reason 622 if (!pnpResult.isPresent()) 623 return update( 624 result, cameraMatrixOpt, distCoeffsOpt, Optional.empty(), this.multiTagFallbackStrategy); 625 var best = Pose3d.kZero.plus(pnpResult.get().best); // field-to-robot 626 627 return Optional.of( 628 new EstimatedRobotPose( 629 best, 630 result.getTimestampSeconds(), 631 result.getTargets(), 632 PoseStrategy.CONSTRAINED_SOLVEPNP)); 633 } 634 635 private Optional<EstimatedRobotPose> multiTagOnCoprocStrategy(PhotonPipelineResult result) { 636 if (result.getMultiTagResult().isEmpty()) { 637 return update(result, this.multiTagFallbackStrategy); 638 } 639 640 var best_tf = result.getMultiTagResult().get().estimatedPose.best; 641 var best = 642 Pose3d.kZero 643 .plus(best_tf) // field-to-camera 644 .relativeTo(fieldTags.getOrigin()) 645 .plus(robotToCamera.inverse()); // field-to-robot 646 return Optional.of( 647 new EstimatedRobotPose( 648 best, 649 result.getTimestampSeconds(), 650 result.getTargets(), 651 PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR)); 652 } 653 654 private Optional<EstimatedRobotPose> multiTagOnRioStrategy( 655 PhotonPipelineResult result, 656 Optional<Matrix<N3, N3>> cameraMatrixOpt, 657 Optional<Matrix<N8, N1>> distCoeffsOpt) { 658 if (cameraMatrixOpt.isEmpty() || distCoeffsOpt.isEmpty()) { 659 DriverStation.reportWarning( 660 "No camera calibration data provided for multi-tag-on-rio", 661 Thread.currentThread().getStackTrace()); 662 return update(result, this.multiTagFallbackStrategy); 663 } 664 665 if (result.getTargets().size() < 2) { 666 return update(result, this.multiTagFallbackStrategy); 667 } 668 669 var pnpResult = 670 VisionEstimation.estimateCamPosePNP( 671 cameraMatrixOpt.get(), distCoeffsOpt.get(), result.getTargets(), fieldTags, tagModel); 672 // try fallback strategy if solvePNP fails for some reason 673 if (!pnpResult.isPresent()) 674 return update( 675 result, cameraMatrixOpt, distCoeffsOpt, Optional.empty(), this.multiTagFallbackStrategy); 676 677 var best = 678 Pose3d.kZero 679 .plus(pnpResult.get().best) // field-to-camera 680 .plus(robotToCamera.inverse()); // field-to-robot 681 682 return Optional.of( 683 new EstimatedRobotPose( 684 best, 685 result.getTimestampSeconds(), 686 result.getTargets(), 687 PoseStrategy.MULTI_TAG_PNP_ON_RIO)); 688 } 689 690 /** 691 * Return the estimated position of the robot with the lowest position ambiguity from a List of 692 * pipeline results. 693 * 694 * @param result pipeline result 695 * @return the estimated position of the robot in the FCS and the estimated timestamp of this 696 * estimation. 697 */ 698 private Optional<EstimatedRobotPose> lowestAmbiguityStrategy(PhotonPipelineResult result) { 699 PhotonTrackedTarget lowestAmbiguityTarget = null; 700 701 double lowestAmbiguityScore = 10; 702 703 for (PhotonTrackedTarget target : result.targets) { 704 double targetPoseAmbiguity = target.getPoseAmbiguity(); 705 // Make sure the target is a Fiducial target. 706 if (targetPoseAmbiguity != -1 && targetPoseAmbiguity < lowestAmbiguityScore) { 707 lowestAmbiguityScore = targetPoseAmbiguity; 708 lowestAmbiguityTarget = target; 709 } 710 } 711 712 // Although there are confirmed to be targets, none of them may be fiducial 713 // targets. 714 if (lowestAmbiguityTarget == null) return Optional.empty(); 715 716 int targetFiducialId = lowestAmbiguityTarget.getFiducialId(); 717 718 Optional<Pose3d> targetPosition = fieldTags.getTagPose(targetFiducialId); 719 720 if (targetPosition.isEmpty()) { 721 reportFiducialPoseError(targetFiducialId); 722 return Optional.empty(); 723 } 724 725 return Optional.of( 726 new EstimatedRobotPose( 727 targetPosition 728 .get() 729 .transformBy(lowestAmbiguityTarget.getBestCameraToTarget().inverse()) 730 .transformBy(robotToCamera.inverse()), 731 result.getTimestampSeconds(), 732 result.getTargets(), 733 PoseStrategy.LOWEST_AMBIGUITY)); 734 } 735 736 /** 737 * Return the estimated position of the robot using the target with the lowest delta height 738 * difference between the estimated and actual height of the camera. 739 * 740 * @param result pipeline result 741 * @return the estimated position of the robot in the FCS and the estimated timestamp of this 742 * estimation. 743 */ 744 private Optional<EstimatedRobotPose> closestToCameraHeightStrategy(PhotonPipelineResult result) { 745 double smallestHeightDifference = 10e9; 746 EstimatedRobotPose closestHeightTarget = null; 747 748 for (PhotonTrackedTarget target : result.targets) { 749 int targetFiducialId = target.getFiducialId(); 750 751 // Don't report errors for non-fiducial targets. This could also be resolved by 752 // adding -1 to 753 // the initial HashSet. 754 if (targetFiducialId == -1) continue; 755 756 Optional<Pose3d> targetPosition = fieldTags.getTagPose(target.getFiducialId()); 757 758 if (targetPosition.isEmpty()) { 759 reportFiducialPoseError(target.getFiducialId()); 760 continue; 761 } 762 763 double alternateTransformDelta = 764 Math.abs( 765 robotToCamera.getZ() 766 - targetPosition 767 .get() 768 .transformBy(target.getAlternateCameraToTarget().inverse()) 769 .getZ()); 770 double bestTransformDelta = 771 Math.abs( 772 robotToCamera.getZ() 773 - targetPosition 774 .get() 775 .transformBy(target.getBestCameraToTarget().inverse()) 776 .getZ()); 777 778 if (alternateTransformDelta < smallestHeightDifference) { 779 smallestHeightDifference = alternateTransformDelta; 780 closestHeightTarget = 781 new EstimatedRobotPose( 782 targetPosition 783 .get() 784 .transformBy(target.getAlternateCameraToTarget().inverse()) 785 .transformBy(robotToCamera.inverse()), 786 result.getTimestampSeconds(), 787 result.getTargets(), 788 PoseStrategy.CLOSEST_TO_CAMERA_HEIGHT); 789 } 790 791 if (bestTransformDelta < smallestHeightDifference) { 792 smallestHeightDifference = bestTransformDelta; 793 closestHeightTarget = 794 new EstimatedRobotPose( 795 targetPosition 796 .get() 797 .transformBy(target.getBestCameraToTarget().inverse()) 798 .transformBy(robotToCamera.inverse()), 799 result.getTimestampSeconds(), 800 result.getTargets(), 801 PoseStrategy.CLOSEST_TO_CAMERA_HEIGHT); 802 } 803 } 804 805 // Need to null check here in case none of the provided targets are fiducial. 806 return Optional.ofNullable(closestHeightTarget); 807 } 808 809 /** 810 * Return the estimated position of the robot using the target with the lowest delta in the vector 811 * magnitude between it and the reference pose. 812 * 813 * @param result pipeline result 814 * @param referencePose reference pose to check vector magnitude difference against. 815 * @return the estimated position of the robot in the FCS and the estimated timestamp of this 816 * estimation. 817 */ 818 private Optional<EstimatedRobotPose> closestToReferencePoseStrategy( 819 PhotonPipelineResult result, Pose3d referencePose) { 820 if (referencePose == null) { 821 DriverStation.reportError( 822 "[PhotonPoseEstimator] Tried to use reference pose strategy without setting the reference!", 823 false); 824 return Optional.empty(); 825 } 826 827 double smallestPoseDelta = 10e9; 828 EstimatedRobotPose lowestDeltaPose = null; 829 830 for (PhotonTrackedTarget target : result.targets) { 831 int targetFiducialId = target.getFiducialId(); 832 833 // Don't report errors for non-fiducial targets. This could also be resolved by 834 // adding -1 to 835 // the initial HashSet. 836 if (targetFiducialId == -1) continue; 837 838 Optional<Pose3d> targetPosition = fieldTags.getTagPose(target.getFiducialId()); 839 840 if (targetPosition.isEmpty()) { 841 reportFiducialPoseError(targetFiducialId); 842 continue; 843 } 844 845 Pose3d altTransformPosition = 846 targetPosition 847 .get() 848 .transformBy(target.getAlternateCameraToTarget().inverse()) 849 .transformBy(robotToCamera.inverse()); 850 Pose3d bestTransformPosition = 851 targetPosition 852 .get() 853 .transformBy(target.getBestCameraToTarget().inverse()) 854 .transformBy(robotToCamera.inverse()); 855 856 double altDifference = Math.abs(calculateDifference(referencePose, altTransformPosition)); 857 double bestDifference = Math.abs(calculateDifference(referencePose, bestTransformPosition)); 858 859 if (altDifference < smallestPoseDelta) { 860 smallestPoseDelta = altDifference; 861 lowestDeltaPose = 862 new EstimatedRobotPose( 863 altTransformPosition, 864 result.getTimestampSeconds(), 865 result.getTargets(), 866 PoseStrategy.CLOSEST_TO_REFERENCE_POSE); 867 } 868 if (bestDifference < smallestPoseDelta) { 869 smallestPoseDelta = bestDifference; 870 lowestDeltaPose = 871 new EstimatedRobotPose( 872 bestTransformPosition, 873 result.getTimestampSeconds(), 874 result.getTargets(), 875 PoseStrategy.CLOSEST_TO_REFERENCE_POSE); 876 } 877 } 878 return Optional.ofNullable(lowestDeltaPose); 879 } 880 881 /** 882 * Return the average of the best target poses using ambiguity as weight. 883 * 884 * @param result pipeline result 885 * @return the estimated position of the robot in the FCS and the estimated timestamp of this 886 * estimation. 887 */ 888 private Optional<EstimatedRobotPose> averageBestTargetsStrategy(PhotonPipelineResult result) { 889 List<Pair<PhotonTrackedTarget, Pose3d>> estimatedRobotPoses = new ArrayList<>(); 890 double totalAmbiguity = 0; 891 892 for (PhotonTrackedTarget target : result.targets) { 893 int targetFiducialId = target.getFiducialId(); 894 895 // Don't report errors for non-fiducial targets. This could also be resolved by 896 // adding -1 to 897 // the initial HashSet. 898 if (targetFiducialId == -1) continue; 899 900 Optional<Pose3d> targetPosition = fieldTags.getTagPose(target.getFiducialId()); 901 902 if (targetPosition.isEmpty()) { 903 reportFiducialPoseError(targetFiducialId); 904 continue; 905 } 906 907 double targetPoseAmbiguity = target.getPoseAmbiguity(); 908 909 // Pose ambiguity is 0, use that pose 910 if (targetPoseAmbiguity == 0) { 911 return Optional.of( 912 new EstimatedRobotPose( 913 targetPosition 914 .get() 915 .transformBy(target.getBestCameraToTarget().inverse()) 916 .transformBy(robotToCamera.inverse()), 917 result.getTimestampSeconds(), 918 result.getTargets(), 919 PoseStrategy.AVERAGE_BEST_TARGETS)); 920 } 921 922 totalAmbiguity += 1.0 / target.getPoseAmbiguity(); 923 924 estimatedRobotPoses.add( 925 new Pair<>( 926 target, 927 targetPosition 928 .get() 929 .transformBy(target.getBestCameraToTarget().inverse()) 930 .transformBy(robotToCamera.inverse()))); 931 } 932 933 // Take the average 934 935 Translation3d transform = new Translation3d(); 936 Rotation3d rotation = new Rotation3d(); 937 938 if (estimatedRobotPoses.isEmpty()) return Optional.empty(); 939 940 for (Pair<PhotonTrackedTarget, Pose3d> pair : estimatedRobotPoses) { 941 // Total ambiguity is non-zero confirmed because if it was zero, that pose was 942 // returned. 943 double weight = (1.0 / pair.getFirst().getPoseAmbiguity()) / totalAmbiguity; 944 Pose3d estimatedPose = pair.getSecond(); 945 transform = transform.plus(estimatedPose.getTranslation().times(weight)); 946 rotation = rotation.plus(estimatedPose.getRotation().times(weight)); 947 } 948 949 return Optional.of( 950 new EstimatedRobotPose( 951 new Pose3d(transform, rotation), 952 result.getTimestampSeconds(), 953 result.getTargets(), 954 PoseStrategy.AVERAGE_BEST_TARGETS)); 955 } 956 957 /** 958 * Difference is defined as the vector magnitude between the two poses 959 * 960 * @return The absolute "difference" (>=0) between two Pose3ds. 961 */ 962 private double calculateDifference(Pose3d x, Pose3d y) { 963 return x.getTranslation().getDistance(y.getTranslation()); 964 } 965 966 private void reportFiducialPoseError(int fiducialId) { 967 if (!reportedErrors.contains(fiducialId)) { 968 DriverStation.reportError( 969 "[PhotonPoseEstimator] Tried to get pose of unknown AprilTag: " + fiducialId, false); 970 reportedErrors.add(fiducialId); 971 } 972 } 973}