Package boofcv.alg.structure
Class ProjectiveInitializeAllCommon
java.lang.Object
boofcv.alg.structure.ProjectiveInitializeAllCommon
- All Implemented Interfaces:
VerbosePrint
public class ProjectiveInitializeAllCommon extends Object implements VerbosePrint
Given a set of views and a set of features which are visible in all views, estimate their structure up to a
projective transform. Summary of processing steps:
- Select initial set of 3 views
- Association between all 3 views
- RANSAC to find Trifocal Tensor
- 3 Projective from trifocal
- Triangulate features
- Find remaining projective camera matrices
- Refine with bundle adjustment
getStructure()
and
getPairwiseGraphViewByStructureIndex(int)
-
Field Summary
Fields Modifier and Type Field Description protected DogArray<AssociatedPair>
assocPixel
protected DogArray<DogArray_I32>
inlierIndexes
List of feature indexes for each view that are part of the inlier set.protected DogArray<Point4D_F64>
points3D
protected DogArray_I32
seedToStructure
lookup table from feature ID in seed view to structure index.protected int[]
selectedTriple
protected ImageDimension
shape
PairwiseGraphUtils
utils
Common algorithms for reconstructing the projective sceneprotected FastArray<PairwiseImageGraph.View>
viewsByStructureIndex
-
Constructor Summary
Constructors Constructor Description ProjectiveInitializeAllCommon()
ProjectiveInitializeAllCommon(ConfigProjectiveReconstruction configProjective)
-
Method Summary
Modifier and Type Method Description protected void
createObservationsForBundleAdjustment(DogArray_I32 seedConnIdx)
Convert observations into a format which bundle adjustment will understandPairwiseImageGraph.View
getPairwiseGraphViewByStructureIndex(int index)
Returns thePairwiseImageGraph.View
given the index of the view in structureSceneStructureProjective
getStructure()
Returns the estimated scene structurevoid
lookupInfoForMetricElevation(List<String> viewIds, DogArray<ElevateViewInfo> views, DogArray<DMatrixRMaj> cameraMatrices, DogArray<AssociatedTupleDN> observations)
Copies results into a format that's useful for projective to metric conversionboolean
projectiveSceneN(LookUpSimilarImages dbSimilar, LookUpCameraInfo dbCams, PairwiseImageGraph.View seed, DogArray_I32 seedFeatsIdx, DogArray_I32 seedConnIdx)
Computes a projective reconstruction.void
setVerbose(@Nullable PrintStream out, @Nullable Set<String> configuration)
-
Field Details
-
utils
Common algorithms for reconstructing the projective scene -
inlierIndexes
List of feature indexes for each view that are part of the inlier set. The seed view is at index 0. The other indexes are in order of 'seedConnIdx'. -
viewsByStructureIndex
-
selectedTriple
protected final int[] selectedTriple -
points3D
-
assocPixel
-
shape
-
seedToStructure
lookup table from feature ID in seed view to structure index. There will only be 3D features for members of the inlier set.
-
-
Constructor Details
-
ProjectiveInitializeAllCommon
-
ProjectiveInitializeAllCommon
public ProjectiveInitializeAllCommon()
-
-
Method Details
-
projectiveSceneN
public boolean projectiveSceneN(LookUpSimilarImages dbSimilar, LookUpCameraInfo dbCams, PairwiseImageGraph.View seed, DogArray_I32 seedFeatsIdx, DogArray_I32 seedConnIdx)Computes a projective reconstruction. Reconstruction will be relative the 'seed' and only use features listed in 'common'. The list of views is taken from seed and is specified in 'motions'.- Parameters:
dbSimilar
- (Input) Data based used to look up information on each imageseed
- (Input) The seed view that will act as the originseedFeatsIdx
- (Input) Indexes of common features in the seed view which are to be used.seedConnIdx
- (Input) Indexes of motions in the seed view to use when initializing- Returns:
- true is successful or false if it failed
-
createObservationsForBundleAdjustment
Convert observations into a format which bundle adjustment will understand- Parameters:
seedConnIdx
- Which edges in seed to use
-
lookupInfoForMetricElevation
public void lookupInfoForMetricElevation(List<String> viewIds, DogArray<ElevateViewInfo> views, DogArray<DMatrixRMaj> cameraMatrices, DogArray<AssociatedTupleDN> observations)Copies results into a format that's useful for projective to metric conversion- Parameters:
viewIds
- (Output) ID of each viewviews
- (Output) Shape of images in each viewcameraMatrices
- (Output) Found camera matrices. view[0] is skipped since it is identityobservations
- (Output) Found observations shifted to have (0,0) center
-
getStructure
Returns the estimated scene structure -
getPairwiseGraphViewByStructureIndex
Returns thePairwiseImageGraph.View
given the index of the view in structure -
setVerbose
public void setVerbose(@Nullable @Nullable PrintStream out, @Nullable @Nullable Set<String> configuration)- Specified by:
setVerbose
in interfaceVerbosePrint
-