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
,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
Modifier and TypeFieldDescriptionedu.wpi.first.math.geometry.Transform3d
Alternate, ambiguous solution from solvepnp.double
If no alternate solution is found, this is bestReprojErrdouble
If no alternate solution is found, this is 0edu.wpi.first.math.geometry.Transform3d
The best-fit transform.double
Reprojection error of the best solution, in pixelsstatic final PnpResultSerde
static final PNPResultProto
-
Constructor Summary
-
Method Summary
-
Field Details
-
best
public 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 double bestReprojErrReprojection error of the best solution, in pixels -
alt
public 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 double altReprojErrIf no alternate solution is found, this is bestReprojErr -
ambiguity
public double ambiguityIf no alternate solution is found, this is 0 -
proto
-
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