PhotonTrackedTarget
- class photonvision.PhotonTrackedTarget(*args, **kwargs)
Bases:
pybind11_object
Represents a tracked target within a pipeline.
Overloaded function.
__init__(self: photonvision._photonvision.PhotonTrackedTarget) -> None
Constructs an empty target.
__init__(self: photonvision._photonvision.PhotonTrackedTarget, yaw: float, pitch: float, area: float, skew: float, fiducialID: int, pose: wpimath.geometry._geometry.Transform3d, alternatePose: wpimath.geometry._geometry.Transform3d, ambiguity: float, corners: List[Tuple[float, float]], detectedCorners: List[Tuple[float, float]]) -> None
Constructs a target.
- Parameters:
yaw – The yaw of the target.
pitch – The pitch of the target.
area – The area of the target.
skew – The skew of the target.
pose – The camera-relative pose of the target.
alternatePose – The alternate camera-relative pose of the target. @Param corners The corners of the bounding rectangle.
- getAlternateCameraToTarget() wpimath.geometry._geometry.Transform3d
Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag space (X forward, Y left, Z up) with the highest reprojection error
- getArea() float
Returns the target area (0-100).
- Returns:
The target area.
- getBestCameraToTarget() wpimath.geometry._geometry.Transform3d
Get the transform that maps camera space (X = forward, Y = left, Z = up) to object/fiducial tag space (X forward, Y left, Z up) with the lowest reprojection error. The ratio between this and the alternate target’s reprojection error is the ambiguity, which is between 0 and 1.
- Returns:
The pose of the target relative to the robot.
- getDetectedCorners() List[Tuple[float, float]]
Return a list of the n corners in image space (origin top left, x right, y down), in no particular order, detected for this target. For fiducials, the order is known and is always counter-clock wise around the tag, like so
-> +X 3 —– 2 | | | V + Y | | 0 —– 1
- getFiducialId() int
Get the Fiducial ID of the target currently being tracked, or -1 if not set.
- getMinAreaRectCorners() List[Tuple[float, float]]
Return a list of the 4 corners in image space (origin top left, x right, y down), in no particular order, of the minimum area bounding rectangle of this target
- getPitch() float
Returns the target pitch (positive-up)
- Returns:
The target pitch.
- getPoseAmbiguity() float
Get the ratio of pose reprojection errors, called ambiguity. Numbers above 0.2 are likely to be ambiguous. -1 if invalid.
- getSkew() float
Returns the target skew (counter-clockwise positive).
- Returns:
The target skew.
- getYaw() float
Returns the target yaw (positive-left).
- Returns:
The target yaw.