Package boofcv.alg.sfm.structure2
Class ProjectiveInitializeAllCommon
- java.lang.Object
-
- boofcv.alg.sfm.structure2.ProjectiveInitializeAllCommon
-
public class ProjectiveInitializeAllCommon extends java.lang.ObjectGiven 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
-
-
Field Summary
Fields Modifier and Type Field Description boofcv.factory.geo.ConfigTrifocalErrorconfigErrorboofcv.factory.geo.ConfigRansacconfigRansacboofcv.factory.geo.ConfigBundleAdjustmentconfigSBAboofcv.factory.geo.ConfigTrifocalconfigTriRansacboofcv.misc.ConfigConvergeconvergeorg.ejml.data.DMatrixRMajP1Projective camera matrices for 3-View reconstruction.org.ejml.data.DMatrixRMajP2Projective camera matrices for 3-View reconstruction.org.ejml.data.DMatrixRMajP3Projective camera matrices for 3-View reconstruction.boofcv.alg.geo.pose.PoseFromPairLinear6poseEstimatororg.ddogleg.fitting.modelset.ransac.Ransac<boofcv.struct.geo.TrifocalTensor,boofcv.struct.geo.AssociatedTriple>ransacboofcv.abst.geo.bundle.BundleAdjustment<boofcv.abst.geo.bundle.SceneStructureProjective>sbaboofcv.abst.geo.bundle.ScaleSceneStructurescalerbooleanscaleSBAboofcv.abst.geo.bundle.SceneStructureProjectivestructureboofcv.abst.geo.TriangulateNViewsProjectivetriangulator
-
Constructor Summary
Constructors Constructor Description ProjectiveInitializeAllCommon()
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description voidfixate()Must call if you change configurations.booleanprojectiveCameras3(LookupSimilarImages db, PairwiseImageGraph2.View viewA, int motionIdxB, int motionIdxC)Computes projective camera matrices for the 3 connected views.booleanprojectiveSceneN(LookupSimilarImages db, PairwiseImageGraph2.View seed, org.ddogleg.struct.GrowQueue_I32 seedFeatsIdx, org.ddogleg.struct.GrowQueue_I32 seedConnIdx)Computes a projective reconstruction.voidsetVerbose(java.io.PrintStream verbose, int level)Adjusts the level of verbosity for debugging
-
-
-
Field Detail
-
configRansac
public boofcv.factory.geo.ConfigRansac configRansac
-
configTriRansac
public boofcv.factory.geo.ConfigTrifocal configTriRansac
-
configError
public boofcv.factory.geo.ConfigTrifocalError configError
-
configSBA
public boofcv.factory.geo.ConfigBundleAdjustment configSBA
-
converge
public boofcv.misc.ConfigConverge converge
-
scaleSBA
public boolean scaleSBA
-
structure
public boofcv.abst.geo.bundle.SceneStructureProjective structure
-
ransac
public org.ddogleg.fitting.modelset.ransac.Ransac<boofcv.struct.geo.TrifocalTensor,boofcv.struct.geo.AssociatedTriple> ransac
-
triangulator
public boofcv.abst.geo.TriangulateNViewsProjective triangulator
-
poseEstimator
public boofcv.alg.geo.pose.PoseFromPairLinear6 poseEstimator
-
sba
public boofcv.abst.geo.bundle.BundleAdjustment<boofcv.abst.geo.bundle.SceneStructureProjective> sba
-
scaler
public boofcv.abst.geo.bundle.ScaleSceneStructure scaler
-
P1
public final org.ejml.data.DMatrixRMaj P1
Projective camera matrices for 3-View reconstruction. P1 is always identity
-
P2
public final org.ejml.data.DMatrixRMaj P2
Projective camera matrices for 3-View reconstruction. P1 is always identity
-
P3
public final org.ejml.data.DMatrixRMaj P3
Projective camera matrices for 3-View reconstruction. P1 is always identity
-
-
Method Detail
-
fixate
public void fixate()
Must call if you change configurations.
-
projectiveSceneN
public boolean projectiveSceneN(LookupSimilarImages db, PairwiseImageGraph2.View seed, org.ddogleg.struct.GrowQueue_I32 seedFeatsIdx, org.ddogleg.struct.GrowQueue_I32 seedConnIdx)
Computes a projective reconstruction. Reconstruction will be relative the 'seed' and only used features listed in 'common'. The list of views is taken from seed and is specified in 'motions'.- Parameters:
seed- The seed view that will act as the originseedFeatsIdx- Indexes of common features in the seed view which are to be used.seedConnIdx- Indexes of motions in the seed view to use when initializing- Returns:
- true is successful
-
projectiveCameras3
public boolean projectiveCameras3(LookupSimilarImages db, PairwiseImageGraph2.View viewA, int motionIdxB, int motionIdxC)
Computes projective camera matrices for the 3 connected views. No bundle adjustment or triangulation 1) Find features with continuous tracks across all 3 views 2) Robustly compute trifocal tensor 3) Extract compatible camera matrices- Parameters:
viewA- The origin viewmotionIdxB- index on edge in viewA for viewBmotionIdxC- index on edge in viewA for viewC- Returns:
- true is successful
-
setVerbose
public void setVerbose(java.io.PrintStream verbose, int level)Adjusts the level of verbosity for debugging
-
-