Class TwoViewToCalibratingHomography

java.lang.Object
boofcv.alg.geo.selfcalib.TwoViewToCalibratingHomography

public class TwoViewToCalibratingHomography extends Object
Estimates the calibrating/rectifying homography when given a trifocal tensor and two calibration matrices for the first two views. Observations are used to select the best hypothesis out of the four possible camera motions. Procedure:
  1. Get fundamental and camera matrices from trifocal tensor
  2. Use given calibration matrices to compute essential matrix
  3. Decompose essential matrix to get 4 possible motions from view 1 to view 2
  4. Use reprojection error and visibility constraints to select best hypothesis
Reprojection error is computed by triangulating each point in view-1 using views-1 and view-2. This is then switched to view-3's reference frame and the reprojection error found there. A similar process is repeated using triangulation from view-1 and view-3. In each view it's checked if the feature appears behind the camera and increments the invalid counter if it does. When selecting a hypothesis the hypothesis with the most points appearing in front of call cameras is given priority over lower reprojection error. When applied to view 2, the found translation should have a norm(T) = 1.
  1. P. Abeles, "BoofCV Technical Report: Automatic Camera Calibration" 2020-1
  • Field Details

    • triangulate

      public Triangulate2ViewsMetric triangulate
      used to triangulate feature locations when checking a solution
    • decomposeEssential

      public final DecomposeEssential decomposeEssential
    • P2

      public final DMatrixRMaj P2
    • F21

      public final DMatrixRMaj F21
    • E21

      public final DMatrixRMaj E21
    • hypothesesH

      public final DogArray<DMatrixRMaj> hypothesesH
      List of all hopotheses for calibrating homography
    • bestSolutionIdx

      public int bestSolutionIdx
      Which hypothesis was selected as the best. Call getCalibrationHomography() as an alternative
    • bestInvalid

      public int bestInvalid
      The number of invalid observations that appeared behind the camera in the best hypothesis
    • bestModelError

      public double bestModelError
      The metric fit error found in view-2 for the best hypothesis. Computed from SVD
  • Constructor Details

    • TwoViewToCalibratingHomography

      public TwoViewToCalibratingHomography()
  • Method Details

    • initialize

      public void initialize(DMatrixRMaj F21, DMatrixRMaj P2)
      Specify known geometric relationship between the two views
      Parameters:
      F21 - (Input) Fundamental matrix between view-1 and view-2
      P2 - (Input) Projective camera matrix for view-1 with inplicit identity matrix view-1
    • process

      public boolean process(DMatrixRMaj K1, DMatrixRMaj K2, List<AssociatedPair> observations)
      Estimate the calibrating homography with the given assumptions about the intrinsic calibration matrices for the first two of three views.
      Parameters:
      K1 - (input) known intrinsic camera calibration matrix for view-1
      K2 - (input) known intrinsic camera calibration matrix for view-2
      observations - (input) observations for the two views. Used to select best solution
      Returns:
      true if it could find a solution. Failure is a rare condition which requires noise free data.
    • getCalibrationHomography

      public DMatrixRMaj getCalibrationHomography()
      Returns the found calibration/rectifying homography.