AprilTagPoseEstimator

class robotpy_apriltag.AprilTagPoseEstimator(config: robotpy_apriltag._apriltag.AprilTagPoseEstimator.Config)

Bases: pybind11_object

Pose estimators for AprilTag tags.

Creates estimator.

Parameters:

config – Configuration

class Config(tagSize: meters, fx: float, fy: float, cx: float, cy: float)

Bases: pybind11_object

Configuration for the pose estimator.

property cx

Camera horizontal focal center, in pixels.

property cy

Camera vertical focal center, in pixels.

property fx

Camera horizontal focal length, in pixels.

property fy

Camera vertical focal length, in pixels.

property tagSize

The tag size.

estimate(*args, **kwargs)

Overloaded function.

  1. estimate(self: robotpy_apriltag._apriltag.AprilTagPoseEstimator, detection: robotpy_apriltag._apriltag.AprilTagDetection) -> wpimath.geometry._geometry.Transform3d

Estimates tag pose. This method is an easier to use interface to EstimatePoseOrthogonalIteration(), running 50 iterations and returning the pose with the lower object-space error.

Parameters:

detection – Tag detection

Returns:

Pose estimate

  1. estimate(self: robotpy_apriltag._apriltag.AprilTagPoseEstimator, homography: Tuple[float, float, float, float, float, float, float, float, float], corners: Tuple[float, float, float, float, float, float, float, float]) -> wpimath.geometry._geometry.Transform3d

Estimates tag pose. This method is an easier to use interface to EstimatePoseOrthogonalIteration(), running 50 iterations and returning the pose with the lower object-space error.

Parameters:
  • homography – Homography 3x3 matrix data

  • corners – Corner point array (X and Y for each corner in order)

Returns:

Pose estimate

estimateHomography(*args, **kwargs)

Overloaded function.

  1. estimateHomography(self: robotpy_apriltag._apriltag.AprilTagPoseEstimator, detection: robotpy_apriltag._apriltag.AprilTagDetection) -> wpimath.geometry._geometry.Transform3d

Estimates the pose of the tag using the homography method described in [1].

Parameters:

detection – Tag detection

Returns:

Pose estimate

  1. estimateHomography(self: robotpy_apriltag._apriltag.AprilTagPoseEstimator, homography: Tuple[float, float, float, float, float, float, float, float, float]) -> wpimath.geometry._geometry.Transform3d

Estimates the pose of the tag using the homography method described in [1].

Parameters:

homography – Homography 3x3 matrix data

Returns:

Pose estimate

estimateOrthogonalIteration(*args, **kwargs)

Overloaded function.

  1. estimateOrthogonalIteration(self: robotpy_apriltag._apriltag.AprilTagPoseEstimator, detection: robotpy_apriltag._apriltag.AprilTagDetection, nIters: int) -> robotpy_apriltag._apriltag.AprilTagPoseEstimate

Estimates the pose of the tag. This returns one or two possible poses for the tag, along with the object-space error of each.

This uses the homography method described in [1] for the initial estimate. Then Orthogonal Iteration [2] is used to refine this estimate. Then [3] is used to find a potential second local minima and Orthogonal Iteration is used to refine this second estimate.

[1]: E. Olson, “Apriltag: A robust and flexible visual fiducial system,” in 2011 IEEE International Conference on Robotics and Automation, May 2011, pp. 3400–3407. [2]: Lu, G. D. Hager and E. Mjolsness, “Fast and globally convergent pose estimation from video images,” in IEEE Transactions on Pattern Analysis and Machine Intelligence, vol. 22, no. 6, pp. 610-622, June 2000. doi: 10.1109/34.862199 [3]: Schweighofer and A. Pinz, “Robust Pose Estimation from a Planar Target,” in IEEE Transactions on Pattern Analysis and Machine Intelligence, vol. 28, no. 12, pp. 2024-2030, Dec. 2006. doi: 10.1109/TPAMI.2006.252

Parameters:
  • detection – Tag detection

  • nIters – Number of iterations

Returns:

Initial and (possibly) second pose estimates

  1. estimateOrthogonalIteration(self: robotpy_apriltag._apriltag.AprilTagPoseEstimator, homography: Tuple[float, float, float, float, float, float, float, float, float], corners: Tuple[float, float, float, float, float, float, float, float], nIters: int) -> robotpy_apriltag._apriltag.AprilTagPoseEstimate

Estimates the pose of the tag. This returns one or two possible poses for the tag, along with the object-space error of each.

Parameters:
  • homography – Homography 3x3 matrix data

  • corners – Corner point array (X and Y for each corner in order)

  • nIters – Number of iterations

Returns:

Initial and (possibly) second pose estimates

getConfig() robotpy_apriltag._apriltag.AprilTagPoseEstimator.Config

Gets estimator configuration.

Returns:

Configuration

setConfig(config: robotpy_apriltag._apriltag.AprilTagPoseEstimator.Config) None

Sets estimator configuration.

Parameters:

config – Configuration