Class VisOdomBundlePnPBase<Track extends VisOdomBundleAdjustment.BTrack>

  • All Implemented Interfaces:
    org.ddogleg.struct.VerbosePrint
    Direct Known Subclasses:
    VisOdomDualTrackPnP, VisOdomMonoDepthPnP

    public abstract class VisOdomBundlePnPBase<Track extends VisOdomBundleAdjustment.BTrack>
    extends java.lang.Object
    implements org.ddogleg.struct.VerbosePrint
    Base class for all visual odometry algorithms based on PNP and use bundle adjustment.
    • Field Detail

      • thresholdRetireTracks

        protected int thresholdRetireTracks
        discard tracks after they have not been in the inlier set for this many updates in a row
      • maxKeyFrames

        public int maxKeyFrames
        Maximum number of allowed key frames in the scene
      • minObservationsTriangulate

        public int minObservationsTriangulate
        Minimum number of feature to be triangulated which was not included in bundle adjustment.
      • minObservationsNotVisible

        public int minObservationsNotVisible
        Drop 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.
      • frameManager

        protected VisOdomKeyFrameManager frameManager
        Decides when to create a new keyframe and discard them
      • current_to_previous

        protected final georegression.struct.se.Se3_F64 current_to_previous
      • previous_to_current

        protected final georegression.struct.se.Se3_F64 previous_to_current
      • current_to_world

        protected final georegression.struct.se.Se3_F64 current_to_world
        transform from the current camera view to the world frame
      • first

        protected boolean first
      • triangulateN

        protected boofcv.abst.geo.TriangulateNViewsMetric triangulateN
        Triangulates points not optimized by bundle adjustment
      • profileOut

        protected java.io.PrintStream profileOut
      • verbose

        protected java.io.PrintStream verbose
      • totalDroppedTracksBadBundle

        protected int totalDroppedTracksBadBundle
      • observationsNorm

        protected org.ddogleg.struct.FastQueue<georegression.struct.point.Point2D_F64> observationsNorm
      • listOf_world_to_frame

        protected org.ddogleg.struct.FastQueue<georegression.struct.se.Se3_F64> listOf_world_to_frame
      • found3D

        protected georegression.struct.point.Point3D_F64 found3D
      • world_to_frame

        protected georegression.struct.se.Se3_F64 world_to_frame
      • cameraLoc

        protected georegression.struct.point.Point4D_F64 cameraLoc
    • Constructor Detail

      • VisOdomBundlePnPBase

        public VisOdomBundlePnPBase()
    • Method Detail

      • 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

        protected boolean performKeyFrameMaintenance​(boofcv.abst.tracker.PointTracker<?> tracker,
                                                     int newFrames)
        Drops specified keyframes from the scene. Returns true if the current frame was dropped
        Parameters:
        tracker - tracker
        newFrames - Number of new frames added to the scene
        Returns:
        true if current frame
      • dropFramesFromScene

        protected void dropFramesFromScene​(org.ddogleg.struct.GrowQueue_I32 dropFrameIndexes)
        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

        protected abstract void dropVisualTrack​(boofcv.abst.tracker.PointTrack track)
        Given the BTrack drop all visual tracks which belong to it.
      • setVerbose

        public void setVerbose​(@Nullable
                               java.io.PrintStream out,
                               @Nullable
                               java.util.Set<java.lang.String> configuration)
        Specified by:
        setVerbose in interface org.ddogleg.struct.VerbosePrint
      • getCurrentToWorld

        public georegression.struct.se.Se3_F64 getCurrentToWorld()
      • getFrameID

        public abstract long getFrameID()