Package boofcv.alg.mvs
Class MultiViewStereoFromKnownSceneStructure<T extends ImageGray<T>>
java.lang.Object
boofcv.alg.mvs.MultiViewStereoFromKnownSceneStructure<T>
- All Implemented Interfaces:
VerbosePrint
public class MultiViewStereoFromKnownSceneStructure<T extends ImageGray<T>>
extends Object
implements VerbosePrint
Creates a dense point cloud from multiple stereo pairs. When possible, a single disparity image is computed using
multiple stereo pairs with a single "center" image that is common to all pairs. This allows noise to be reduced
using the redundant information. A combined 3D point cloud is then found using multiple disparity images while
removing redundant points.
- Compute the score for every view if it was a "center" view among multiple stereo pairs
- Sort views based on scores with the best first
- Greedily select views to act as a center view and compute a combined disparity image from its neighbors
- Add a disparity image to the combined 3D point cloud while pruning pixels which are too similar
getCloud()
is what you need. If information on each view's
contribution to the point cloud is needed then you need to call #getDisparityCloud()
and access
the view specific results.
NOTE: Before this can be used you must call setStereoDisparity(boofcv.abst.disparity.StereoDisparity<T, boofcv.struct.image.GrayF32>)
.-
Nested Class Summary
Modifier and TypeClassDescriptionstatic interface
Used to capture intermediate resultsstatic class
Information on each view that's used to select and compute the disparity images -
Field Summary
Modifier and TypeFieldDescriptionprotected LookUpImages
protected final List<MultiViewStereoFromKnownSceneStructure.ViewInfo>
Which views acted as "centers" and contributed to the point cloudprotected @Nullable MultiViewStereoFromKnownSceneStructure.Listener<T>
Used to access temporary results before they are discardedint
Maximum number of stereo pairs that will be combined.double
Maximum amount of screen space two connected views can have and both of them be a center.double
Specifies the minimum quality of the 3D information between two views for it to be used as a stereo pair. -
Constructor Summary
ConstructorDescriptionMultiViewStereoFromKnownSceneStructure
(LookUpImages imageLookUp, ImageType<T> imageType) MultiViewStereoFromKnownSceneStructure
(ImageType<T> imageType) -
Method Summary
Modifier and TypeMethodDescriptionprotected double
computeIntersection
(SceneStructureMetric scene, @Nullable SceneObservations observations, MultiViewStereoFromKnownSceneStructure.ViewInfo connected) Computes how much the two rectified images intersect each othergetCloud()
Returns the computed 3D point cloud.void
process
(SceneStructureMetric scene, @Nullable SceneObservations observations, StereoPairGraph pairs) Computes a point cloud given the known scene and a set of stereo pairs.protected void
pruneViewsThatAreSimilarByNeighbors
(SceneStructureMetric scene, @Nullable SceneObservations observations) Marks a view as used so that it can't be used as a center if most of the view is "covered" by another view which has a higher score and most of the view area is covered by other views.void
setImageLookUp
(LookUpImages imageLookUp) void
setStereoDisparity
(StereoDisparity<T, GrayF32> stereoDisparity) Specifies which stereo disparity algorithm to usevoid
setVerbose
(@Nullable PrintStream out, @Nullable Set<String> configuration)
-
Field Details
-
minimumQuality3D
public double minimumQuality3DSpecifies the minimum quality of the 3D information between two views for it to be used as a stereo pair.- See Also:
-
maximumCenterOverlap
public double maximumCenterOverlapMaximum amount of screen space two connected views can have and both of them be a center. Inclusive. 0 to 1.0 -
maxCombinePairs
public int maxCombinePairsMaximum number of stereo pairs that will be combined. If more than this number then the best are selected -
listener
@Nullable protected @Nullable MultiViewStereoFromKnownSceneStructure.Listener<T extends ImageGray<T>> listenerUsed to access temporary results before they are discarded -
listCenters
Which views acted as "centers" and contributed to the point cloud -
imageLookUp
-
-
Constructor Details
-
MultiViewStereoFromKnownSceneStructure
-
MultiViewStereoFromKnownSceneStructure
-
-
Method Details
-
process
public void process(SceneStructureMetric scene, @Nullable @Nullable SceneObservations observations, StereoPairGraph pairs) Computes a point cloud given the known scene and a set of stereo pairs.- Parameters:
scene
- (Input) Specifies the scene parameters for each view. Extrinsic and intrinsic.observations
- (Input) Specifies the observed state of the camera.pairs
- (Input) Which views are to be used and their relationship to each other
-
pruneViewsThatAreSimilarByNeighbors
protected void pruneViewsThatAreSimilarByNeighbors(SceneStructureMetric scene, @Nullable @Nullable SceneObservations observations) Marks a view as used so that it can't be used as a center if most of the view is "covered" by another view which has a higher score and most of the view area is covered by other views. The exception to this rule is if there are a significant number of pixels not covered by any neighbors. -
computeIntersection
protected double computeIntersection(SceneStructureMetric scene, @Nullable @Nullable SceneObservations observations, MultiViewStereoFromKnownSceneStructure.ViewInfo connected) Computes how much the two rectified images intersect each other- Returns:
- fraction of intersection, 0.0 to 1.0
-
getCloud
Returns the computed 3D point cloud. -
setStereoDisparity
Specifies which stereo disparity algorithm to use -
setImageLookUp
-
setVerbose
public void setVerbose(@Nullable @Nullable PrintStream out, @Nullable @Nullable Set<String> configuration) - Specified by:
setVerbose
in interfaceVerbosePrint
-