Package org.photonvision.targeting
Class PNPResult
java.lang.Object
org.photonvision.targeting.PNPResult
- All Implemented Interfaces:
edu.wpi.first.util.protobuf.ProtobufSerializable
,edu.wpi.first.util.WPISerializable
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
-
Field Summary
Modifier and TypeFieldDescriptionfinal edu.wpi.first.math.geometry.Transform3d
Alternate, ambiguous solution from solvepnp.final double
If no alternate solution is found, this is bestReprojErrfinal double
If no alternate solution is found, this is 0final edu.wpi.first.math.geometry.Transform3d
The best-fit transform.final double
Reprojection error of the best solution, in pixelsfinal boolean
If this result is valid.static final PNPResultProto
static final PNPResult.APacketSerde
-
Constructor Summary
-
Method Summary
-
Field Details
-
isPresent
public final boolean isPresentIf 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 bestThe best-fit transform. The coordinate frame of this transform depends on the method which gave this result. -
bestReprojErr
public final double bestReprojErrReprojection error of the best solution, in pixels -
alt
public final edu.wpi.first.math.geometry.Transform3d altAlternate, ambiguous solution from solvepnp. If no alternate solution is found, this is equal to the best solution. -
altReprojErr
public final double altReprojErrIf no alternate solution is found, this is bestReprojErr -
ambiguity
public final double ambiguityIf no alternate solution is found, this is 0 -
serde
-
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