Package boofcv.alg.sfm.d3
Class VisOdomBundlePnPBase<Track extends VisOdomBundleAdjustment.BTrack>
java.lang.Object
boofcv.alg.sfm.d3.VisOdomBundlePnPBase<Track>
- All Implemented Interfaces:
VerbosePrint
- Direct Known Subclasses:
VisOdomDualTrackPnP
,VisOdomMonoDepthPnP
public abstract class VisOdomBundlePnPBase<Track extends VisOdomBundleAdjustment.BTrack>
extends Object
implements VerbosePrint
Base class for all visual odometry algorithms based on PNP and use bundle adjustment.
-
Nested Class Summary
Modifier and TypeClassDescriptionprotected static class
Contains the camera's lens distortion model -
Field Summary
Modifier and TypeFieldDescriptionprotected VisOdomBundleAdjustment<Track>
Describes the entire 3D scene's structure and optimizes with bundle adjustmentprotected Point4D_F64
protected final List<VisOdomBundlePnPBase.CameraModel>
Lens distortion fpr the camerasprotected final Se3_F64
protected final Se3_F64
transform from the current camera view to the world frameprotected boolean
protected Point3D_F64
protected VisOdomKeyFrameManager
Decides when to create a new keyframe and discard themlocation of tracks in the image that are included in the inlier setint
Maximum number of allowed key frames in the sceneint
Drop tracks which are no longer visible if their total number of observations is less than this number.int
Minimum number of feature to be triangulated which was not included in bundle adjustment.protected DogArray<Point2D_F64>
protected final Se3_F64
protected @Nullable PrintStream
protected int
discard tracks after they have not been in the inlier set for this many updates in a rowprotected int
protected TriangulateNViewsMetric
Triangulates points not optimized by bundle adjustmentprotected @Nullable PrintStream
Tracks which are visible in the most recently processed frameprotected Se3_F64
-
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionprotected void
dropFramesFromScene
(DogArray_I32 dropFrameIndexes) Removes the frames listed from the sceneprotected void
Drop tracks which are no longer being visually tracked and have less than two observations.protected abstract void
dropVisualTrack
(PointTrack track) Given the BTrack drop all visual tracks which belong to it.abstract long
protected boolean
performKeyFrameMaintenance
(PointTracker<?> tracker, int newFrames) Drops specified keyframes from the scene.void
reset()
Resets the algorithm into its original statevoid
setVerbose
(@Nullable PrintStream out, @Nullable Set<String> configuration) protected void
Triangulate tracks which were not included in the optimizationprotected void
Goes through the list of initially visible tracks and see which ones have not been dropped
-
Field Details
-
thresholdRetireTracks
protected int thresholdRetireTracksdiscard tracks after they have not been in the inlier set for this many updates in a row -
maxKeyFrames
public int maxKeyFramesMaximum number of allowed key frames in the scene -
minObservationsTriangulate
public int minObservationsTriangulateMinimum number of feature to be triangulated which was not included in bundle adjustment. -
minObservationsNotVisible
public int minObservationsNotVisibleDrop tracks which are no longer visible if their total number of observations is less than this number. At a minimum this can be 2, but 3 is recommended for stability. -
bundleViso
Describes the entire 3D scene's structure and optimizes with bundle adjustment -
frameManager
Decides when to create a new keyframe and discard them -
inlierTracks
location of tracks in the image that are included in the inlier set -
visibleTracks
Tracks which are visible in the most recently processed frame -
initialVisible
-
current_to_previous
-
previous_to_current
-
current_to_world
transform from the current camera view to the world frame -
first
protected boolean first -
cameraModels
Lens distortion fpr the cameras -
triangulateN
Triangulates points not optimized by bundle adjustment -
profileOut
-
verbose
-
totalDroppedTracksBadBundle
protected int totalDroppedTracksBadBundle -
observationsNorm
-
listOf_world_to_frame
-
found3D
-
world_to_frame
-
cameraLoc
-
-
Constructor Details
-
VisOdomBundlePnPBase
public VisOdomBundlePnPBase()
-
-
Method Details
-
reset
public void reset()Resets the algorithm into its original state -
updateListOfVisibleTracksForOutput
protected void updateListOfVisibleTracksForOutput()Goes through the list of initially visible tracks and see which ones have not been dropped -
triangulateNotSelectedBundleTracks
protected void triangulateNotSelectedBundleTracks()Triangulate tracks which were not included in the optimization -
performKeyFrameMaintenance
Drops specified keyframes from the scene. Returns true if the current frame was dropped- Parameters:
tracker
- trackernewFrames
- Number of new frames added to the scene- Returns:
- true if current frame
-
dropFramesFromScene
Removes the frames listed from the scene- Parameters:
dropFrameIndexes
- List of indexes to drop. Sorted from lowest to highest
-
dropTracksNotVisibleAndTooFewObservations
protected void dropTracksNotVisibleAndTooFewObservations()Drop tracks which are no longer being visually tracked and have less than two observations. In general 3 observations is much more stable than two and less prone to be a false positive. -
dropVisualTrack
Given the BTrack drop all visual tracks which belong to it. -
setVerbose
public void setVerbose(@Nullable @Nullable PrintStream out, @Nullable @Nullable Set<String> configuration) - Specified by:
setVerbose
in interfaceVerbosePrint
-
getCurrentToWorld
-
getFrameID
public abstract long getFrameID()
-