Class FactoryMultiView

java.lang.Object
boofcv.factory.geo.FactoryMultiView

public class FactoryMultiView extends Object
Factory for creating abstracted algorithms related to multi-view geometry
  • Constructor Details

    • FactoryMultiView

      public FactoryMultiView()
  • Method Details

    • bundleSparseMetric

      public static BundleAdjustment<SceneStructureMetric> bundleSparseMetric(@Nullable @Nullable ConfigBundleAdjustment config)
      Returns bundle adjustment with a sparse implementation for metric reconstruction. In most situations this is what you want to use, however dense bundle adjustment is available if the problem is small and degenerate.
      Parameters:
      config - (Optional) configuration
      Returns:
      bundle adjustment
    • bundleSparseProjective

      public static BundleAdjustment<SceneStructureProjective> bundleSparseProjective(@Nullable @Nullable ConfigBundleAdjustment config)
      Returns bundle adjustment with a sparse implementation for projective reconstruction. In most situations this is what you want to use, however dense bundle adjustment is available if the problem is small and degenerate.
      Parameters:
      config - (Optional) configuration
      Returns:
      bundle adjustment
    • bundleDenseMetric

      public static BundleAdjustment<SceneStructureMetric> bundleDenseMetric(boolean robust, @Nullable @Nullable ConfigBundleAdjustment config)
      Returns bundle adjustment with a dense implementation for metric reconstruction. While much slower than a sparse solver, a dense solver can handle systems which are degenerate.
      Parameters:
      robust - If true a smaller but robust solver will be used.
      config - (Optional) configuration
      Returns:
      bundle adjustment
    • bundleDenseProjective

      public static BundleAdjustment<SceneStructureProjective> bundleDenseProjective(boolean robust, @Nullable @Nullable ConfigBundleAdjustment config)
      Returns bundle adjustment with a sparse implementation for projective reconstruction. In most stiuations this is what you want to use, however dense bundle adjustment is available if the problem is small and degenerate.
      Parameters:
      robust - If true a smaller but robust solver will be used.
      config - (Optional) configuration
      Returns:
      bundle adjustment
    • homographyDLT

      public static HomographyDLT_to_Epipolar homographyDLT(boolean normalizeInput)
      Returns an algorithm for estimating a homography matrix given a set of AssociatedPair.
      Parameters:
      normalizeInput - If input is in pixel coordinates set to true. False if in normalized image coordinates.
      Returns:
      Homography estimator.
      See Also:
    • homographyTLS

      public static HomographyTLS_to_Epipolar homographyTLS()
      Returns an algorithm for estimating a homography matrix given a set of AssociatedPair.
      Returns:
      Homography estimator.
      See Also:
    • homographyWithRadial

      public static HomographyRadial6Pts homographyWithRadial()
      Estimator that will find the homography and radial distortion terms. Models lens with CameraDivision and requires at least 6 points.
      Returns:
      Homography + radial distortion estimator.
      See Also:
    • homographyRefine

      public static LeastSquaresHomography homographyRefine(double tol, int maxIterations, EpipolarError type)
      Creates a non-linear optimizer for refining estimates of homography matrices.
      Parameters:
      tol - Tolerance for convergence. Try 1e-8
      maxIterations - Maximum number of iterations it will perform. Try 100 or more.
      Returns:
      Homography refinement
      See Also:
    • fundamental_N

      public static EstimateNofEpipolar fundamental_N(EnumFundamental which)

      Returns an algorithm for estimating a fundamental or essential matrix given a set of AssociatedPair in pixel coordinates. The number of hypotheses returned and minimum number of samples is dependent on the implementation. The ambiguity from multiple hypotheses can be resolved using other sample points and testing additional constraints.

      All estimated epipolar matrices will have the following constraint:
      x'*F*x = 0, where F is the epipolar matrix, x' = currLoc, and x = keyLoc.

      There are more differences between these algorithms than the minimum number of sample points. Consult the literature for information on critical surfaces which will work or not work with each algorithm. In general, algorithm which require fewer samples have less issues with critical surfaces than the 8-point algorithm.

      IMPORTANT: When estimating a fundamental matrix use pixel coordinates. When estimating an essential matrix use normalized image coordinates from a calibrated camera.

      IMPORTANT. The number of allowed sample points varies depending on the algorithm. The 8 point algorithm can process 8 or more points. Both the 5 an 7 point algorithms require exactly 5 and 7 points exactly. In addition the 5-point algorithm is only for the calibrated (essential) case.

      Parameters:
      which - Specifies which algorithm is to be created
      Returns:
      Fundamental or essential estimation algorithm that returns multiple hypotheses.
      See Also:
    • essential_N

      public static EstimateNofEpipolar essential_N(EnumEssential which)
      Estimates an essential matrix given observations as normalized image coordinates. All N solutions are returned
    • essentialPointing_N

      public static EstimateNofEpipolarPointing essentialPointing_N(EnumEssential which)
      Estimates an essential matrix given observations as pointing vectors
    • fundamental_1

      public static Estimate1ofEpipolar fundamental_1(EnumFundamental which, int numRemoveAmbiguity)

      Similar to fundamental_N(boofcv.factory.geo.EnumFundamental), but it returns only a single hypothesis. If the underlying algorithm generates multiple hypotheses they are resolved by considering additional sample points. For example, if you are using the 7 point algorithm at least one additional sample point is required to resolve that ambiguity. So 8 or more sample points are now required.

      All estimated epipolar matrices will have the following constraint:
      x'*F*x = 0, where F is the epipolar matrix, x' = currLoc, and x = keyLoc.

      See fundamental_N(boofcv.factory.geo.EnumFundamental) for a description of the algorithms and what 'minimumSamples' and 'isFundamental' do.

      The 8-point algorithm already returns a single hypothesis and ignores the 'numRemoveAmbiguity' parameter. All other algorithms require one or more points to remove ambiguity. Understanding a bit of theory is required to understand what a good number of points is. If a single point is used then to select the correct answer that point must be in the inlier set. If more than one point, say 10, then not all of those points must be in the inlier set,

      Parameters:
      which - Specifies which algorithm is to be created
      numRemoveAmbiguity - Number of sample points used to prune hypotheses. Ignored if only a single solution.
      Returns:
      Fundamental or essential estimation algorithm that returns a single hypothesis.
      See Also:
    • essential_1

      public static Estimate1ofEpipolar essential_1(EnumEssential which, int numRemoveAmbiguity)
    • essentialPointing_1

      public static EstimateNto1ofEpipolarPointing essentialPointing_1(EnumEssential which, int numRemoveAmbiguity)
    • fundamentalRefine

      public static RefineEpipolar fundamentalRefine(double tol, int maxIterations, EpipolarError type)
      Creates a non-linear optimizer for refining estimates of fundamental or essential matrices.
      Parameters:
      tol - Tolerance for convergence. Try 1e-8
      maxIterations - Maximum number of iterations it will perform. Try 100 or more.
      Returns:
      RefineEpipolar
      See Also:
    • trifocal_1

      public static Estimate1ofTrifocalTensor trifocal_1(@Nullable @Nullable ConfigTrifocal config)
      Creates a trifocal tensor estimation algorithm.
      Parameters:
      config - configuration for the estimator
      Returns:
      Trifocal tensor estimator
    • threeViewRefine

      public static RefineThreeViewProjective threeViewRefine(@Nullable @Nullable ConfigThreeViewRefine config)
      Used to refine three projective views. This is the same as refining a trifocal tensor.
      Returns:
      RefineThreeViewProjective
    • pnp_N

      public static EstimateNofPnP pnp_N(EnumPNP which, int numIterations)
      Creates an estimator for the PnP problem that uses only three observations, which is the minimal case and known as P3P.

      NOTE: Observations are in normalized image coordinates NOT pixels.

      Parameters:
      which - The algorithm which is to be returned.
      numIterations - Number of iterations. Only used by some algorithms and recommended number varies significantly by algorithm.
      Returns:
      An estimator which can return multiple estimates.
    • pnp_1

      public static Estimate1ofPnP pnp_1(EnumPNP which, int numIterations, int numTest)
      Created an estimator for the P3P problem that selects a single solution by considering additional observations.

      NOTE: Observations are in normalized image coordinates NOT pixels.

      NOTE: EPnP has several tuning parameters and the defaults here might not be the best for your situation. Use computePnPwithEPnP(int, double) if you wish to have access to all parameters.

      Parameters:
      which - The algorithm which is to be returned.
      numIterations - Number of iterations. Only used by some algorithms and recommended number varies significantly by algorithm.
      numTest - How many additional sample points are used to remove ambiguity in the solutions. Not used if only a single solution is found.
      Returns:
      An estimator which returns a single estimate.
    • prnp_1

      public static Estimate1ofPrNP prnp_1()
      Projective N Point. This is PnP for uncalibrated cameras. Please read algorithms documentation for limitations
      Returns:
      Estimator
      See Also:
    • computePnPwithEPnP

      public static Estimate1ofPnP computePnPwithEPnP(int numIterations, double magicNumber)
      Returns a solution to the PnP problem for 4 or more points using EPnP. Fast and fairly accurate algorithm. Can handle general and planar scenario automatically.

      NOTE: Observations are in normalized image coordinates NOT pixels.

      Parameters:
      numIterations - If more then zero then non-linear optimization is done. More is not always better. Try 10
      magicNumber - Affects how the problem is linearized. See comments in PnPLepetitEPnP. Try 0.1
      Returns:
      Estimate1ofPnP
      See Also:
    • pnpRefine

      public static RefinePnP pnpRefine(double tol, int maxIterations)
      Refines a pose solution to the PnP problem using non-linear least squares..
      Parameters:
      tol - Convergence tolerance. Try 1e-8
      maxIterations - Maximum number of iterations. Try 200
    • poseFromPair

      public static PoseFromPairLinear6 poseFromPair()
      Estimate the camera motion give two observations and the 3D world coordinate of each points.
      Returns:
      PoseFromPairLinear6
    • triangulate2ViewMetric

      public static Triangulate2ViewsMetric triangulate2ViewMetric(@Nullable @Nullable ConfigTriangulation config)
      Triangulate two view using the Discrete Linear Transform (DLT) with a calibrated camera.
      Returns:
      Two view triangulation algorithm
      See Also:
    • triangulate2ViewMetricH

      public static Triangulate2ViewsMetricH triangulate2ViewMetricH(@Nullable @Nullable ConfigTriangulation config)
      Triangulate two view using the Discrete Linear Transform (DLT) with a calibrated camera.
      Returns:
      Two view triangulation algorithm
      See Also:
    • triangulate2ViewProjective

      public static Triangulate2ViewsProjective triangulate2ViewProjective(@Nullable @Nullable ConfigTriangulation config)
      Triangulate two view using the Discrete Linear Transform (DLT) with an uncalibrated camera.
      Returns:
      Two view triangulation algorithm
      See Also:
    • triangulateNViewMetric

      public static TriangulateNViewsMetric triangulateNViewMetric(@Nullable @Nullable ConfigTriangulation config)
      Triangulate N views using the Discrete Linear Transform (DLT) with a calibrated camera
      Returns:
      N-view triangulation algorithm
      See Also:
    • triangulateNViewMetricH

      public static TriangulateNViewsMetricH triangulateNViewMetricH(@Nullable @Nullable ConfigTriangulation config)
      Triangulate a homogenous point from N metric views given observations in normalized image coordinates.
      Returns:
      N-view triangulation algorithm
      See Also:
    • triangulateNViewProj

      public static TriangulateNViewsProjective triangulateNViewProj(@Nullable @Nullable ConfigTriangulation config)
      Triangulate a homogenous point from N projective views given observations in pixel coordinates.
      Returns:
      N-view triangulation algorithm
      See Also:
    • triangulate2PointingMetricH

      public static Triangulate2PointingMetricH triangulate2PointingMetricH(@Nullable @Nullable ConfigTriangulation config)
      Triangulate a point in homogeneous coordinates using two pointing vector observations.
      Returns:
      Two view triangulation algorithm
      See Also:
    • triangulateNPointingMetricH

      public static TriangulateNPointingMetricH triangulateNPointingMetricH(@Nullable @Nullable ConfigTriangulation config)
      Triangulate a point in homogenous coordinates from N views given observations as pointing vectors.
      Returns:
      N-view triangulation algorithm
      See Also:
    • triangulateRefineEpipolar

      public static RefineTriangulateEpipolar triangulateRefineEpipolar(ConfigConverge config)
      Refine the triangulation using Sampson error. Approximately takes in account epipolar constraints.
      Parameters:
      config - Convergence criteria
      Returns:
      Triangulation refinement algorithm.
      See Also:
    • triangulateRefineMetric

      public static RefineTriangulateMetric triangulateRefineMetric(ConfigConverge config)
      Refine the triangulation by computing the difference between predicted and actual pixel location. Does not take in account epipolar constraints.
      Parameters:
      config - Convergence criteria
      Returns:
      Triangulation refinement algorithm.
      See Also:
    • triangulateRefineMetricH

      public static RefineTriangulateMetricH triangulateRefineMetricH(ConfigConverge config)
      Refine the triangulation by computing the difference between predicted and actual pixel location. Does not take in account epipolar constraints.
      Parameters:
      config - Convergence criteria
      Returns:
      Triangulation refinement algorithm.
      See Also:
    • triangulateRefineProj

      public static RefineTriangulateProjective triangulateRefineProj(ConfigConverge config)
      Refines a projective triangulation
      Parameters:
      config - Convergence criteria
      Returns:
      Triangulation refinement algorithm.
      See Also:
    • selfCalibThree

      public static ModelGeneratorViews<MetricCameraTriple,AssociatedTriple,ElevateViewInfo> selfCalibThree(@Nullable @Nullable ConfigPixelsToMetric config)
      Three-view self calibration based on various methods. Read documentation carefully since partially known calibration is the norm and often the principle point needs to be zero.
      Parameters:
      config - (Input) Configuration for metric elevation. Can be null.
      Returns:
      ModelGenerator
    • projectiveToMetric

      public static ProjectiveToMetricCameras projectiveToMetric(@Nullable @Nullable ConfigSelfCalibDualQuadratic config)
      Parameters:
      config - (Input) Configuration. Can be null.
      Returns:
      ProjectiveToMetricCameras
    • projectiveToMetric

      public static ProjectiveToMetricCameras projectiveToMetric(@Nullable @Nullable ConfigSelfCalibEssentialGuess config)
      Parameters:
      config - (Input) Configuration. Can be null.
      Returns:
      ProjectiveToMetricCameras
    • projectiveToMetric

      public static ProjectiveToMetricCameras projectiveToMetric(@Nullable @Nullable ConfigSelfCalibPracticalGuess config)
      Parameters:
      config - (Input) Configuration. Can be null.
      Returns:
      ProjectiveToMetricCameras
    • refineDualAbsoluteQuadratic

      public static RefineDualQuadraticAlgebraicError refineDualAbsoluteQuadratic(ConfigConverge config)
      Returns RefineDualQuadraticAlgebraicError which can be used to minimize the Dual Quadratic by minimizing algebraic error.
      Parameters:
      config - Converge criteria