Package boofcv.alg.mvs
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:- Input: The scene (view locations, camera parameters), image references, center image, and stereo pairs
- For each paired image:
- Rectify
- Compute the disparity
- Pass to MBS disparity algorithm
- 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.
-
Nested Class Summary
Modifier and TypeClassDescriptionstatic interface
Used to gain access to intermediate results -
Field Summary
Modifier and TypeFieldDescriptionint
Removes disparity from around the original image's border in rectified image.double
Scale factor for adaptive disparity error threshold -
Constructor Summary
ConstructorDescriptionMultiBaselineStereoIndependent
(LookUpImages lookUpImages, ImageType<Image> imageType) MultiBaselineStereoIndependent
(ImageType<Image> imageType) -
Method Summary
Modifier and TypeMethodDescriptionReturns intrinsic camera parameters for the targeted viewboolean
process
(SceneStructureMetric scene, @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.void
setVerbose
(@Nullable PrintStream out, @Nullable Set<String> configuration)
-
Field Details
-
disparityErrorThresholdScale
public double disparityErrorThresholdScaleScale factor for adaptive disparity error threshold -
disparityBlockRadius
public int disparityBlockRadiusRemoves 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
-
MultiBaselineStereoIndependent
-
-
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 viewtargetIdx
- The "center" view which is common to all stereo pairspairIdxs
- List of views (as indexes) which will act as the second image in the stereo pairssbaIndexToViewID
- 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 interfaceVerbosePrint
-
getTargetIntrinsic
Returns intrinsic camera parameters for the targeted view
-