001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.apriltag;
006
007import edu.wpi.first.apriltag.jni.AprilTagJNI;
008import edu.wpi.first.math.geometry.Transform3d;
009
010/** Pose estimators for AprilTag tags. */
011public class AprilTagPoseEstimator {
012  /** Configuration for the pose estimator. */
013  @SuppressWarnings("MemberName")
014  public static class Config {
015    /**
016     * Creates a pose estimator configuration.
017     *
018     * @param tagSize tag size, in meters
019     * @param fx camera horizontal focal length, in pixels
020     * @param fy camera vertical focal length, in pixels
021     * @param cx camera horizontal focal center, in pixels
022     * @param cy camera vertical focal center, in pixels
023     */
024    public Config(double tagSize, double fx, double fy, double cx, double cy) {
025      this.tagSize = tagSize;
026      this.fx = fx;
027      this.fy = fy;
028      this.cx = cx;
029      this.cy = cy;
030    }
031
032    /** Tag size, in meters. */
033    public double tagSize;
034
035    /** Camera horizontal focal length, in pixels. */
036    public double fx;
037
038    /** Camera vertical focal length, in pixels. */
039    public double fy;
040
041    /** Camera horizontal focal center, in pixels. */
042    public double cx;
043
044    /** Camera vertical focal center, in pixels. */
045    public double cy;
046
047    @Override
048    public int hashCode() {
049      return Double.hashCode(tagSize)
050          + Double.hashCode(fx)
051          + Double.hashCode(fy)
052          + Double.hashCode(cx)
053          + Double.hashCode(cy);
054    }
055
056    @Override
057    public boolean equals(Object obj) {
058      return obj instanceof Config other
059          && tagSize == other.tagSize
060          && fx == other.fx
061          && fy == other.fy
062          && cx == other.cx
063          && cy == other.cy;
064    }
065  }
066
067  /**
068   * Creates estimator.
069   *
070   * @param config Configuration
071   */
072  public AprilTagPoseEstimator(Config config) {
073    m_config = new Config(config.tagSize, config.fx, config.fy, config.cx, config.cy);
074  }
075
076  /**
077   * Sets estimator configuration.
078   *
079   * @param config Configuration
080   */
081  public void setConfig(Config config) {
082    m_config.tagSize = config.tagSize;
083    m_config.fx = config.fx;
084    m_config.fy = config.fy;
085    m_config.cx = config.cx;
086    m_config.cy = config.cy;
087  }
088
089  /**
090   * Gets estimator configuration.
091   *
092   * @return Configuration
093   */
094  public Config getConfig() {
095    return new Config(m_config.tagSize, m_config.fx, m_config.fy, m_config.cx, m_config.cy);
096  }
097
098  /**
099   * Estimates the pose of the tag using the homography method described in [1].
100   *
101   * @param detection Tag detection
102   * @return Pose estimate
103   */
104  public Transform3d estimateHomography(AprilTagDetection detection) {
105    return estimateHomography(detection.getHomography());
106  }
107
108  /**
109   * Estimates the pose of the tag using the homography method described in [1].
110   *
111   * @param homography Homography 3x3 matrix data
112   * @return Pose estimate
113   */
114  public Transform3d estimateHomography(double[] homography) {
115    return AprilTagJNI.estimatePoseHomography(
116        homography, m_config.tagSize, m_config.fx, m_config.fy, m_config.cx, m_config.cy);
117  }
118
119  /**
120   * Estimates the pose of the tag. This returns one or two possible poses for the tag, along with
121   * the object-space error of each.
122   *
123   * <p>This uses the homography method described in [1] for the initial estimate. Then Orthogonal
124   * Iteration [2] is used to refine this estimate. Then [3] is used to find a potential second
125   * local minima and Orthogonal Iteration is used to refine this second estimate.
126   *
127   * <p>[1]: E. Olson, “Apriltag: A robust and flexible visual fiducial system,” in 2011 IEEE
128   * International Conference on Robotics and Automation, May 2011, pp. 3400–3407.
129   *
130   * <p>[2]: Lu, G. D. Hager and E. Mjolsness, "Fast and globally convergent pose estimation from
131   * video images," in IEEE Transactions on Pattern Analysis and Machine Intelligence, vol. 22, no.
132   * 6, pp. 610-622, June 2000. doi: 10.1109/34.862199
133   *
134   * <p>[3]: Schweighofer and A. Pinz, "Robust Pose Estimation from a Planar Target," in IEEE
135   * Transactions on Pattern Analysis and Machine Intelligence, vol. 28, no. 12, pp. 2024-2030, Dec.
136   * 2006. doi: 10.1109/TPAMI.2006.252
137   *
138   * @param detection Tag detection
139   * @param nIters Number of iterations
140   * @return Initial and (possibly) second pose estimates
141   */
142  public AprilTagPoseEstimate estimateOrthogonalIteration(AprilTagDetection detection, int nIters) {
143    return estimateOrthogonalIteration(detection.getHomography(), detection.getCorners(), nIters);
144  }
145
146  /**
147   * Estimates the pose of the tag. This returns one or two possible poses for the tag, along with
148   * the object-space error of each.
149   *
150   * @param homography Homography 3x3 matrix data
151   * @param corners Corner point array (X and Y for each corner in order)
152   * @param nIters Number of iterations
153   * @return Initial and (possibly) second pose estimates
154   */
155  public AprilTagPoseEstimate estimateOrthogonalIteration(
156      double[] homography, double[] corners, int nIters) {
157    return AprilTagJNI.estimatePoseOrthogonalIteration(
158        homography,
159        corners,
160        m_config.tagSize,
161        m_config.fx,
162        m_config.fy,
163        m_config.cx,
164        m_config.cy,
165        nIters);
166  }
167
168  /**
169   * Estimates tag pose. This method is an easier to use interface to
170   * EstimatePoseOrthogonalIteration(), running 50 iterations and returning the pose with the lower
171   * object-space error.
172   *
173   * @param detection Tag detection
174   * @return Pose estimate
175   */
176  public Transform3d estimate(AprilTagDetection detection) {
177    return estimate(detection.getHomography(), detection.getCorners());
178  }
179
180  /**
181   * Estimates tag pose. This method is an easier to use interface to
182   * EstimatePoseOrthogonalIteration(), running 50 iterations and returning the pose with the lower
183   * object-space error.
184   *
185   * @param homography Homography 3x3 matrix data
186   * @param corners Corner point array (X and Y for each corner in order)
187   * @return Pose estimate
188   */
189  public Transform3d estimate(double[] homography, double[] corners) {
190    return AprilTagJNI.estimatePose(
191        homography, corners, m_config.tagSize, m_config.fx, m_config.fy, m_config.cx, m_config.cy);
192  }
193
194  private final Config m_config;
195}