Class PnpResult

java.lang.Object
org.photonvision.targeting.PnpResult
All Implemented Interfaces:
edu.wpi.first.util.protobuf.ProtobufSerializable, edu.wpi.first.util.WPISerializable, PhotonStructSerializable<PnpResult>

public class PnpResult extends Object implements edu.wpi.first.util.protobuf.ProtobufSerializable, PhotonStructSerializable<PnpResult>
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.

  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    edu.wpi.first.math.geometry.Transform3d
    Alternate, ambiguous solution from solvepnp.
    double
    If no alternate solution is found, this is bestReprojErr
    double
    If no alternate solution is found, this is 0
    edu.wpi.first.math.geometry.Transform3d
    The best-fit transform.
    double
    Reprojection error of the best solution, in pixels
    static final PnpResultSerde
     
    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

    • best

      public 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 double bestReprojErr
      Reprojection error of the best solution, in pixels
    • alt

      public 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 double altReprojErr
      If no alternate solution is found, this is bestReprojErr
    • ambiguity

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

      public static final PNPResultProto proto
    • photonStruct

      public static final PnpResultSerde photonStruct
  • 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