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.
  • Field Details

    • 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.
    • bundleViso

      Describes the entire 3D scene's structure and optimizes with bundle adjustment
    • frameManager

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

      protected final List<Track extends VisOdomBundleAdjustment.BTrack> inlierTracks
      location of tracks in the image that are included in the inlier set
    • visibleTracks

      protected final List<Track extends VisOdomBundleAdjustment.BTrack> visibleTracks
      Tracks which are visible in the most recently processed frame
    • initialVisible

      protected final List<Track extends VisOdomBundleAdjustment.BTrack> initialVisible
    • current_to_previous

      protected final Se3_F64 current_to_previous
    • previous_to_current

      protected final Se3_F64 previous_to_current
    • current_to_world

      protected final Se3_F64 current_to_world
      transform from the current camera view to the world frame
    • first

      protected boolean first
    • cameraModels

      protected final List<VisOdomBundlePnPBase.CameraModel> cameraModels
      Lens distortion fpr the cameras
    • triangulateN

      protected TriangulateNViewsMetric triangulateN
      Triangulates points not optimized by bundle adjustment
    • profileOut

      @Nullable protected @Nullable PrintStream profileOut
    • verbose

      @Nullable protected @Nullable PrintStream verbose
    • totalDroppedTracksBadBundle

      protected int totalDroppedTracksBadBundle
    • observationsNorm

      protected DogArray<Point2D_F64> observationsNorm
    • listOf_world_to_frame

      protected DogArray<Se3_F64> listOf_world_to_frame
    • found3D

      protected Point3D_F64 found3D
    • world_to_frame

      protected Se3_F64 world_to_frame
    • cameraLoc

      protected Point4D_F64 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

      protected boolean performKeyFrameMaintenance(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(DogArray_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(PointTrack track)
      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 interface VerbosePrint
    • getCurrentToWorld

      public Se3_F64 getCurrentToWorld()
    • getFrameID

      public abstract long getFrameID()