Package boofcv.alg.sfm.d3.structure
Class MaxGeoKeyFrameManager
- java.lang.Object
-
- boofcv.alg.sfm.d3.structure.MaxGeoKeyFrameManager
-
- All Implemented Interfaces:
VisOdomKeyFrameManager,org.ddogleg.struct.VerbosePrint
public class MaxGeoKeyFrameManager extends java.lang.Object implements VisOdomKeyFrameManager
Designed to be frame rate independent and maximize geometric information across frames. Old frames are kept as long as possible and attempts to drop/skip over bad frames due to motion blur.
-
-
Nested Class Summary
Nested Classes Modifier and Type Class Description protected static classMaxGeoKeyFrameManager.CameraInfo
-
Field Summary
Fields Modifier and Type Field Description protected org.ddogleg.struct.FastArray<boofcv.abst.tracker.PointTrack>activeTracksprotected org.ddogleg.struct.FastQueue<MaxGeoKeyFrameManager.CameraInfo>camerasprotected org.ddogleg.struct.GrowQueue_I32discardKeyIndicesprotected boofcv.alg.misc.Histogram2D_S32histogramdoubleminimumCoverageIf the fraction of the image covered by features drops below this the current frame is a new keyframeprotected java.io.PrintStreamverbose
-
Constructor Summary
Constructors Constructor Description MaxGeoKeyFrameManager()MaxGeoKeyFrameManager(double minimumCoverage)
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description voidhandleSpawnedTracks(boofcv.abst.tracker.PointTracker<?> tracker, VisOdomBundleAdjustment.BCamera camera)After the current frame becomes a keyframe new tracks are spawned from it.voidinitialize(org.ddogleg.struct.FastAccess<VisOdomBundleAdjustment.BCamera> bundleCameras)Resets the manager into it's initial state.protected booleankeepCurrentFrame(VisOdomBundleAdjustment<?> sba)Perform different checks that attempt to see if too much has changed.org.ddogleg.struct.GrowQueue_I32selectFramesToDiscard(boofcv.abst.tracker.PointTracker<?> tracker, int maxKeyFrames, int newFrames, VisOdomBundleAdjustment<?> sba)Selects frames to discard from the scene graph.protected voidselectOldToDiscard(VisOdomBundleAdjustment<?> sba, int totalDiscard)Selects an older frame to discard.voidsetVerbose(java.io.PrintStream out, java.util.Set<java.lang.String> configuration)
-
-
-
Field Detail
-
minimumCoverage
public double minimumCoverage
If the fraction of the image covered by features drops below this the current frame is a new keyframe
-
discardKeyIndices
protected final org.ddogleg.struct.GrowQueue_I32 discardKeyIndices
-
cameras
protected org.ddogleg.struct.FastQueue<MaxGeoKeyFrameManager.CameraInfo> cameras
-
activeTracks
protected org.ddogleg.struct.FastArray<boofcv.abst.tracker.PointTrack> activeTracks
-
histogram
protected boofcv.alg.misc.Histogram2D_S32 histogram
-
verbose
protected java.io.PrintStream verbose
-
-
Method Detail
-
initialize
public void initialize(org.ddogleg.struct.FastAccess<VisOdomBundleAdjustment.BCamera> bundleCameras)
Description copied from interface:VisOdomKeyFrameManagerResets the manager into it's initial state. Specifies number of cameras and their shape.- Specified by:
initializein interfaceVisOdomKeyFrameManager
-
selectFramesToDiscard
public org.ddogleg.struct.GrowQueue_I32 selectFramesToDiscard(boofcv.abst.tracker.PointTracker<?> tracker, int maxKeyFrames, int newFrames, VisOdomBundleAdjustment<?> sba)Description copied from interface:VisOdomKeyFrameManagerSelects frames to discard from the scene graph. The most recent frame(s) (highest index value) is assumed to be the current tracker frame.- Specified by:
selectFramesToDiscardin interfaceVisOdomKeyFrameManager- Parameters:
tracker- Feature trackermaxKeyFrames- Maximum number of allowed key framesnewFrames- Number of new frames addedsba- scene graph- Returns:
- Returns a list of frames to discard. They are in sequential order from least to greatest.
-
keepCurrentFrame
protected boolean keepCurrentFrame(VisOdomBundleAdjustment<?> sba)
Perform different checks that attempt to see if too much has changed. If too much has changed then the current keyframe should be kept so that new features can be spawned and starvation avoided.- Returns:
- true if it should keep the current frame
-
selectOldToDiscard
protected void selectOldToDiscard(VisOdomBundleAdjustment<?> sba, int totalDiscard)
Selects an older frame to discard. If a frame has zero features in common with the current frame it will be selected. After that it scores frames based on how many features it has in common with the other frames, excluding the current frame.- Parameters:
totalDiscard- How many need to be discarded
-
handleSpawnedTracks
public void handleSpawnedTracks(boofcv.abst.tracker.PointTracker<?> tracker, VisOdomBundleAdjustment.BCamera camera)Description copied from interface:VisOdomKeyFrameManagerAfter the current frame becomes a keyframe new tracks are spawned from it. This passes in that new information- Specified by:
handleSpawnedTracksin interfaceVisOdomKeyFrameManager
-
setVerbose
public void setVerbose(@Nullable java.io.PrintStream out, @Nullable java.util.Set<java.lang.String> configuration)- Specified by:
setVerbosein interfaceorg.ddogleg.struct.VerbosePrint
-
-