Class MultiBaselineStereoIndependent<Image extends ImageGray<Image>>

java.lang.Object
boofcv.alg.mvs.MultiBaselineStereoIndependent<Image>
All Implemented Interfaces:
VerbosePrint

public class MultiBaselineStereoIndependent<Image extends ImageGray<Image>> extends Object implements VerbosePrint

Solution for the Multi Baseline Stereo (MBS) problem which uses independently computed stereo disparity images [1] with one common "center" image. Internally it calls another algorithm to decide how to fuse the different options into a single disparity image. The output disparity image is in the original image's pixel coordinates and not a rectified image.

Steps:
  1. Input: The scene (view locations, camera parameters), image references, center image, and stereo pairs
  2. For each paired image:
    1. Rectify
    2. Compute the disparity
    3. Pass to MBS disparity algorithm
  3. Compute single disparity image for output

[1] There is no citation since this wasn't based on any specific paper but created out of a need to reuse existing stereo code based on a high level description of MVS pipeline.

  • Field Details

    • disparityErrorThresholdScale

      public double disparityErrorThresholdScale
      Scale factor for adaptive disparity error threshold
    • disparityBlockRadius

      public int disparityBlockRadius
      Removes disparity from around the original image's border in rectified image. This parameter specifies how big the kernel used to compute the disparity is to avoid artifacts.
  • Constructor Details

    • MultiBaselineStereoIndependent

      public MultiBaselineStereoIndependent(LookUpImages lookUpImages, ImageType<Image> imageType)
    • MultiBaselineStereoIndependent

      public MultiBaselineStereoIndependent(ImageType<Image> imageType)
  • Method Details

    • process

      public boolean process(SceneStructureMetric scene, @Nullable @Nullable SceneObservations observations, int targetIdx, DogArray_I32 pairIdxs, BoofLambdas.IndexToString sbaIndexToViewID)
      Computes the disparity between the target and each of the views it has been paired with then fuses all of these into a single disparity image in the target's original pixel coordinates.
      Parameters:
      scene - Contains extrinsic and intrinsics for each view
      targetIdx - The "center" view which is common to all stereo pairs
      pairIdxs - List of views (as indexes) which will act as the second image in the stereo pairs
      sbaIndexToViewID - Look up table from view index to view ID
      Returns:
      true if successful or false if it failed
    • setVerbose

      public void setVerbose(@Nullable @Nullable PrintStream out, @Nullable @Nullable Set<String> configuration)
      Specified by:
      setVerbose in interface VerbosePrint
    • getTargetIntrinsic

      public CameraPinholeBrown getTargetIntrinsic()
      Returns intrinsic camera parameters for the targeted view