Package boofcv.factory.sfm
Class ConfigVisOdomTrackPnP
java.lang.Object
boofcv.factory.sfm.ConfigVisOdomTrackPnP
- All Implemented Interfaces:
Configuration
,Serializable
Base class for visual odometry algorithms based on
PointTracker
.- See Also:
-
Field Summary
Modifier and TypeFieldDescriptionConfiguration for Bundle AdjustmentConvergence criteria for bundle adjustment.int
Maximum number of features optimized in bundle adjustment per key frame.int
Minimum number of observations a track must have before it is included in bundle adjustment.int
Drop tracks if they have been outliers for this many frames in a rowSpecifies when a new key frame is createdint
Maximum number of key frames it will save.Which PNP solution to useConfiguration for RANSAC.int
Number of iterations to perform when refining the initial frame-to-frame motion estimate. -
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionvoid
Checks to see if the configuration is valid.Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
Methods inherited from interface boofcv.struct.Configuration
serializeActiveFields, serializeInitialize
-
Field Details
-
bundle
Configuration for Bundle Adjustment -
bundleConverge
Convergence criteria for bundle adjustment. Set max iterations to ≤ 0 to disable -
bundleMaxFeaturesPerFrame
public int bundleMaxFeaturesPerFrameMaximum number of features optimized in bundle adjustment per key frame. This is a very good way to limit the amount of CPU used. If not positive then unlimited. ≤ 0 to disable. -
bundleMinObservations
public int bundleMinObservationsMinimum number of observations a track must have before it is included in bundle adjustment. Has to be ≥ 2 and it's strongly recommended that this is set to 3 or higher. Due to ambiguity along epipolar lines there can be lots of false positives with just two views. With three views there is a unique solution and that tends to remove most false positives. -
dropOutlierTracks
public int dropOutlierTracksDrop tracks if they have been outliers for this many frames in a row -
maxKeyFrames
public int maxKeyFramesMaximum number of key frames it will save. Must be at least 4 -
ransac
Configuration for RANSAC. Used to robustly estimate frame-to-frame motion -
refineIterations
public int refineIterationsNumber of iterations to perform when refining the initial frame-to-frame motion estimate. Disable ≤ 0 -
pnp
Which PNP solution to use -
keyframes
Specifies when a new key frame is created
-
-
Constructor Details
-
ConfigVisOdomTrackPnP
public ConfigVisOdomTrackPnP()
-
-
Method Details
-
checkValidity
public void checkValidity()Description copied from interface:Configuration
Checks to see if the configuration is valid. If it is invalid, throw an exception explaining what is incorrect.- Specified by:
checkValidity
in interfaceConfiguration
-
setTo
-