Package boofcv.factory.sfm
Class ConfigStereoQuadPnP
- java.lang.Object
-
- boofcv.factory.sfm.ConfigStereoQuadPnP
-
- All Implemented Interfaces:
boofcv.struct.Configuration,java.io.Serializable
public class ConfigStereoQuadPnP extends java.lang.Object implements boofcv.struct.ConfigurationConfiguration forWrapVisOdomDualTrackPnP.- See Also:
- Serialized Form
-
-
Field Summary
Fields Modifier and Type Field Description boofcv.factory.feature.associate.ConfigAssociateGreedyassociateF2FAssociation approach for matching frames across time stepsboofcv.factory.feature.associate.ConfigAssociateGreedyassociateL2RAssociation approach for matching stereo pairsboofcv.factory.geo.ConfigBundleAdjustmentbundleConfiguration for Bundle Adjustmentboofcv.misc.ConfigConvergebundleConvergeConvergence criteria for bundle adjustment.boofcv.factory.feature.detdesc.ConfigDetectDescribedetectDescribeWhich feature detector / descriptor should it usedoubleepipolarTolTolerance for matching stereo features along epipolar line in Pixelsboofcv.factory.geo.EnumPNPpnpWhich PNP solution to useboofcv.factory.geo.ConfigRansacransacConfiguration for RANSAC.intrefineIterationsNumber of iterations to perform when refining the initial frame-to-frame motion estimate.
-
Constructor Summary
Constructors Constructor Description ConfigStereoQuadPnP()
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description voidcheckValidity()voidsetTo(ConfigStereoQuadPnP src)
-
-
-
Field Detail
-
bundle
public boofcv.factory.geo.ConfigBundleAdjustment bundle
Configuration for Bundle Adjustment
-
bundleConverge
public boofcv.misc.ConfigConverge bundleConverge
Convergence criteria for bundle adjustment. Set max iterations to ≤ 0 to disable
-
pnp
public boofcv.factory.geo.EnumPNP pnp
Which PNP solution to use
-
ransac
public boofcv.factory.geo.ConfigRansac ransac
Configuration for RANSAC. Used to robustly estimate frame-to-frame motion
-
refineIterations
public int refineIterations
Number of iterations to perform when refining the initial frame-to-frame motion estimate. Disable ≤ 0
-
detectDescribe
public boofcv.factory.feature.detdesc.ConfigDetectDescribe detectDescribe
Which feature detector / descriptor should it use
-
associateF2F
public boofcv.factory.feature.associate.ConfigAssociateGreedy associateF2F
Association approach for matching frames across time steps
-
associateL2R
public boofcv.factory.feature.associate.ConfigAssociateGreedy associateL2R
Association approach for matching stereo pairs
-
epipolarTol
public double epipolarTol
Tolerance for matching stereo features along epipolar line in Pixels
-
-
Method Detail
-
setTo
public void setTo(ConfigStereoQuadPnP src)
-
checkValidity
public void checkValidity()
- Specified by:
checkValidityin interfaceboofcv.struct.Configuration
-
-