Class PNPResult

java.lang.Object
org.photonvision.targeting.PNPResult
All Implemented Interfaces:
edu.wpi.first.util.protobuf.ProtobufSerializable, edu.wpi.first.util.WPISerializable

public class PNPResult extends Object implements edu.wpi.first.util.protobuf.ProtobufSerializable
The best estimated transformation from solvePnP, and possibly an alternate transformation depending on the solvePNP method. If an alternate solution is present, the ambiguity value represents the ratio of reprojection error in the best solution to the alternate (best / alternate).

Note that the coordinate frame of these transforms depends on the implementing solvePnP method.

  • Nested Class Summary

    Nested Classes
    Modifier and Type
    Class
    Description
    static final class 
     
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    final edu.wpi.first.math.geometry.Transform3d
    Alternate, ambiguous solution from solvepnp.
    final double
    If no alternate solution is found, this is bestReprojErr
    final double
    If no alternate solution is found, this is 0
    final edu.wpi.first.math.geometry.Transform3d
    The best-fit transform.
    final double
    Reprojection error of the best solution, in pixels
    final boolean
    If this result is valid.
    static final PNPResultProto
     
     
  • Constructor Summary

    Constructors
    Constructor
    Description
    An empty (invalid) result.
    PNPResult(edu.wpi.first.math.geometry.Transform3d best, double bestReprojErr)
     
    PNPResult(edu.wpi.first.math.geometry.Transform3d best, edu.wpi.first.math.geometry.Transform3d alt, double ambiguity, double bestReprojErr, double altReprojErr)
     
  • Method Summary

    Modifier and Type
    Method
    Description
    boolean
     
    int
     
     

    Methods inherited from class java.lang.Object

    clone, finalize, getClass, notify, notifyAll, wait, wait, wait
  • Field Details

    • isPresent

      public final boolean isPresent
      If this result is valid. A false value indicates there was an error in estimation, and this result should not be used.
    • best

      public final edu.wpi.first.math.geometry.Transform3d best
      The best-fit transform. The coordinate frame of this transform depends on the method which gave this result.
    • bestReprojErr

      public final double bestReprojErr
      Reprojection error of the best solution, in pixels
    • alt

      public final edu.wpi.first.math.geometry.Transform3d alt
      Alternate, ambiguous solution from solvepnp. If no alternate solution is found, this is equal to the best solution.
    • altReprojErr

      public final double altReprojErr
      If no alternate solution is found, this is bestReprojErr
    • ambiguity

      public final double ambiguity
      If no alternate solution is found, this is 0
    • serde

      public static final PNPResult.APacketSerde serde
    • proto

      public static final PNPResultProto proto
  • Constructor Details

    • PNPResult

      public PNPResult()
      An empty (invalid) result.
    • PNPResult

      public PNPResult(edu.wpi.first.math.geometry.Transform3d best, double bestReprojErr)
    • PNPResult

      public PNPResult(edu.wpi.first.math.geometry.Transform3d best, edu.wpi.first.math.geometry.Transform3d alt, double ambiguity, double bestReprojErr, double altReprojErr)
  • Method Details