Class FactoryVisualOdometry


  • public class FactoryVisualOdometry
    extends java.lang.Object
    Factory for creating visual odometry algorithms.
    • Method Summary

      All Methods Static Methods Concrete Methods Deprecated Methods 
      Modifier and Type Method Description
      static <Vis extends boofcv.struct.image.ImageGray<Vis>,​Depth extends boofcv.struct.image.ImageGray<Depth>>
      DepthVisualOdometry<Vis,​Depth>
      depthDepthPnP​(double inlierPixelTol, int thresholdAdd, int thresholdRetire, int ransacIterations, int refineIterations, boolean doublePass, DepthSparse3D<Depth> sparseDepth, boofcv.abst.tracker.PointTrackerTwoPass<Vis> tracker, java.lang.Class<Vis> visualType, java.lang.Class<Depth> depthType)
      Deprecated.
      static <Vis extends boofcv.struct.image.ImageGray<Vis>,​Depth extends boofcv.struct.image.ImageGray<Depth>>
      DepthVisualOdometry<Vis,​Depth>
      depthDepthPnP​(ConfigVisOdomTrackPnP configVO, DepthSparse3D<Depth> sparseDepth, boofcv.abst.tracker.PointTracker<Vis> tracker, java.lang.Class<Vis> visualType, java.lang.Class<Depth> depthType)  
      static <Vis extends boofcv.struct.image.ImageGray<Vis>,​Depth extends boofcv.struct.image.ImageGray<Depth>>
      DepthVisualOdometry<boofcv.struct.image.Planar<Vis>,​Depth>
      depthDirect​(DepthSparse3D<Depth> sparse3D, boofcv.struct.image.ImageType<boofcv.struct.image.Planar<Vis>> visualType, java.lang.Class<Depth> depthType)  
      static <T extends boofcv.struct.image.ImageGray<T>>
      MonocularPlaneVisualOdometry<T>
      monoPlaneInfinity​(int thresholdAdd, int thresholdRetire, double inlierPixelTol, int ransacIterations, boofcv.abst.tracker.PointTracker<T> tracker, boofcv.struct.image.ImageType<T> imageType)
      Monocular plane based visual odometry algorithm which uses both points on the plane and off plane for motion estimation.
      static <T extends boofcv.struct.image.ImageGray<T>>
      MonocularPlaneVisualOdometry<T>
      monoPlaneOverhead​(double cellSize, double maxCellsPerPixel, double mapHeightFraction, double inlierGroundTol, int ransacIterations, int thresholdRetire, int absoluteMinimumTracks, double respawnTrackFraction, double respawnCoverageFraction, boofcv.abst.tracker.PointTracker<T> tracker, boofcv.struct.image.ImageType<T> imageType)
      Monocular plane based visual odometry algorithm which creates a synthetic overhead view and tracks image features inside this synthetic view.
      static <T extends boofcv.struct.image.ImageBase<T>>
      MonocularPlaneVisualOdometry<T>
      scaleInput​(MonocularPlaneVisualOdometry<T> vo, double scaleFactor)
      Wraps around a MonocularPlaneVisualOdometry instance and will rescale the input images and adjust the cameras intrinsic parameters automatically.
      static <T extends boofcv.struct.image.ImageBase<T>>
      StereoVisualOdometry<T>
      scaleInput​(StereoVisualOdometry<T> vo, double scaleFactor)
      Wraps around a StereoVisualOdometry instance and will rescale the input images and adjust the cameras intrinsic parameters automatically.
      static <T extends boofcv.struct.image.ImageGray<T>>
      StereoVisualOdometry<T>
      stereoDepth​(double inlierPixelTol, int thresholdAdd, int thresholdRetire, int ransacIterations, int refineIterations, boolean doublePass, boofcv.abst.feature.disparity.StereoDisparitySparse<T> sparseDisparity, boofcv.abst.tracker.PointTracker<T> tracker, java.lang.Class<T> imageType)
      Deprecated.
      static <T extends boofcv.struct.image.ImageGray<T>>
      StereoVisualOdometry<T>
      stereoDualTrackerPnP​(ConfigStereoDualTrackPnP configVO, java.lang.Class<T> imageType)
      Creates an instance of VisOdomDualTrackPnP.
      static <T extends boofcv.struct.image.ImageGray<T>,​Desc extends boofcv.struct.feature.TupleDesc>
      StereoVisualOdometry<T>
      stereoDualTrackerPnP​(ConfigVisOdomTrackPnP configVO, boofcv.abst.tracker.PointTracker<T> trackerLeft, boofcv.abst.tracker.PointTracker<T> trackerRight, ConfigStereoDualTrackPnP hack, java.lang.Class<T> imageType)  
      static <T extends boofcv.struct.image.ImageGray<T>>
      StereoVisualOdometry<T>
      stereoMonoPnP​(ConfigVisOdomTrackPnP configVO, boofcv.abst.feature.disparity.StereoDisparitySparse<T> sparseDisparity, boofcv.abst.tracker.PointTracker<T> tracker, java.lang.Class<T> imageType)
      Stereo vision based visual odometry algorithm which runs a sparse feature tracker in the left camera and estimates the range of tracks once when first detected using disparity between left and right cameras.
      static <T extends boofcv.struct.image.ImageGray<T>,​Desc extends boofcv.struct.feature.TupleDesc>
      StereoVisualOdometry<T>
      stereoQuadPnP​(ConfigStereoQuadPnP config, java.lang.Class<T> imageType)
      Creates a stereo visual odometry algorithm that uses the two most recent frames (4 images total) to estimate motion.
      • Methods inherited from class java.lang.Object

        clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
    • Constructor Detail

      • FactoryVisualOdometry

        public FactoryVisualOdometry()
    • Method Detail

      • monoPlaneInfinity

        public static <T extends boofcv.struct.image.ImageGray<T>> MonocularPlaneVisualOdometry<T> monoPlaneInfinity​(int thresholdAdd,
                                                                                                                     int thresholdRetire,
                                                                                                                     double inlierPixelTol,
                                                                                                                     int ransacIterations,
                                                                                                                     boofcv.abst.tracker.PointTracker<T> tracker,
                                                                                                                     boofcv.struct.image.ImageType<T> imageType)
        Monocular plane based visual odometry algorithm which uses both points on the plane and off plane for motion estimation.
        Type Parameters:
        T -
        Parameters:
        thresholdAdd - New points are spawned when the number of on plane inliers drops below this value.
        thresholdRetire - Tracks are dropped when they are not contained in the inlier set for this many frames in a row. Try 2
        inlierPixelTol - Threshold used to determine inliers in pixels. Try 1.5
        ransacIterations - Number of RANSAC iterations. Try 200
        tracker - Image feature tracker
        imageType - Type of input image it processes
        Returns:
        New instance of
        See Also:
        VisOdomMonoPlaneInfinity
      • monoPlaneOverhead

        public static <T extends boofcv.struct.image.ImageGray<T>> MonocularPlaneVisualOdometry<T> monoPlaneOverhead​(double cellSize,
                                                                                                                     double maxCellsPerPixel,
                                                                                                                     double mapHeightFraction,
                                                                                                                     double inlierGroundTol,
                                                                                                                     int ransacIterations,
                                                                                                                     int thresholdRetire,
                                                                                                                     int absoluteMinimumTracks,
                                                                                                                     double respawnTrackFraction,
                                                                                                                     double respawnCoverageFraction,
                                                                                                                     boofcv.abst.tracker.PointTracker<T> tracker,
                                                                                                                     boofcv.struct.image.ImageType<T> imageType)
        Monocular plane based visual odometry algorithm which creates a synthetic overhead view and tracks image features inside this synthetic view.
        Parameters:
        cellSize - (Overhead) size of ground cells in overhead image in world units
        maxCellsPerPixel - (Overhead) Specifies the minimum resolution. Higher values allow lower resolutions. Try 20
        mapHeightFraction - (Overhead) Truncates the overhead view. Must be from 0 to 1.0. 1.0 includes the entire image.
        inlierGroundTol - (RANSAC) RANSAC tolerance in overhead image pixels
        ransacIterations - (RANSAC) Number of iterations used when estimating motion
        thresholdRetire - (2D Motion) Drop tracks if they are not in inliers set for this many turns.
        absoluteMinimumTracks - (2D Motion) Spawn tracks if the number of inliers drops below the specified number
        respawnTrackFraction - (2D Motion) Spawn tracks if the number of tracks has dropped below this fraction of the original number
        respawnCoverageFraction - (2D Motion) Spawn tracks if the total coverage drops below this relative fraction
        tracker - Image feature tracker
        imageType - Type of image being processed
        Returns:
        MonocularPlaneVisualOdometry
        See Also:
        VisOdomMonoOverheadMotion2D
      • stereoMonoPnP

        public static <T extends boofcv.struct.image.ImageGray<T>> StereoVisualOdometry<T> stereoMonoPnP​(ConfigVisOdomTrackPnP configVO,
                                                                                                         boofcv.abst.feature.disparity.StereoDisparitySparse<T> sparseDisparity,
                                                                                                         boofcv.abst.tracker.PointTracker<T> tracker,
                                                                                                         java.lang.Class<T> imageType)
        Stereo vision based visual odometry algorithm which runs a sparse feature tracker in the left camera and estimates the range of tracks once when first detected using disparity between left and right cameras.
        Parameters:
        configVO - Configuration for visual odometry
        sparseDisparity - Estimates the 3D location of features
        tracker - Image point feature tracker.
        imageType - Type of image being processed.
        Returns:
        StereoVisualOdometry
        See Also:
        VisOdomMonoDepthPnP
      • stereoDepth

        @Deprecated
        public static <T extends boofcv.struct.image.ImageGray<T>> StereoVisualOdometry<T> stereoDepth​(double inlierPixelTol,
                                                                                                       int thresholdAdd,
                                                                                                       int thresholdRetire,
                                                                                                       int ransacIterations,
                                                                                                       int refineIterations,
                                                                                                       boolean doublePass,
                                                                                                       boofcv.abst.feature.disparity.StereoDisparitySparse<T> sparseDisparity,
                                                                                                       boofcv.abst.tracker.PointTracker<T> tracker,
                                                                                                       java.lang.Class<T> imageType)
        Deprecated.
        Stereo vision based visual odometry algorithm which runs a sparse feature tracker in the left camera and estimates the range of tracks once when first detected using disparity between left and right cameras.
        Parameters:
        thresholdAdd - Add new tracks when less than this number are in the inlier set. Tracker dependent. Set to a value ≤ 0 to add features every frame.
        thresholdRetire - Discard a track if it is not in the inlier set after this many updates. Try 2
        sparseDisparity - Estimates the 3D location of features
        imageType - Type of image being processed.
        Returns:
        StereoVisualOdometry
        See Also:
        VisOdomMonoDepthPnP
      • depthDepthPnP

        @Deprecated
        public static <Vis extends boofcv.struct.image.ImageGray<Vis>,​Depth extends boofcv.struct.image.ImageGray<Depth>> DepthVisualOdometry<Vis,​Depth> depthDepthPnP​(double inlierPixelTol,
                                                                                                                                                                                   int thresholdAdd,
                                                                                                                                                                                   int thresholdRetire,
                                                                                                                                                                                   int ransacIterations,
                                                                                                                                                                                   int refineIterations,
                                                                                                                                                                                   boolean doublePass,
                                                                                                                                                                                   DepthSparse3D<Depth> sparseDepth,
                                                                                                                                                                                   boofcv.abst.tracker.PointTrackerTwoPass<Vis> tracker,
                                                                                                                                                                                   java.lang.Class<Vis> visualType,
                                                                                                                                                                                   java.lang.Class<Depth> depthType)
        Deprecated.
        Depth sensor based visual odometry algorithm which runs a sparse feature tracker in the visual camera and estimates the range of tracks once when first detected using the depth sensor.
        Parameters:
        thresholdAdd - Add new tracks when less than this number are in the inlier set. Tracker dependent. Set to a value ≤ 0 to add features every frame.
        thresholdRetire - Discard a track if it is not in the inlier set after this many updates. Try 2
        sparseDepth - Extracts depth of pixels from a depth sensor.
        visualType - Type of visual image being processed.
        depthType - Type of depth image being processed.
        Returns:
        StereoVisualOdometry
        See Also:
        VisOdomMonoDepthPnP
      • depthDepthPnP

        public static <Vis extends boofcv.struct.image.ImageGray<Vis>,​Depth extends boofcv.struct.image.ImageGray<Depth>> DepthVisualOdometry<Vis,​Depth> depthDepthPnP​(ConfigVisOdomTrackPnP configVO,
                                                                                                                                                                                   DepthSparse3D<Depth> sparseDepth,
                                                                                                                                                                                   boofcv.abst.tracker.PointTracker<Vis> tracker,
                                                                                                                                                                                   java.lang.Class<Vis> visualType,
                                                                                                                                                                                   java.lang.Class<Depth> depthType)
      • stereoDualTrackerPnP

        public static <T extends boofcv.struct.image.ImageGray<T>> StereoVisualOdometry<T> stereoDualTrackerPnP​(@Nullable
                                                                                                                ConfigStereoDualTrackPnP configVO,
                                                                                                                java.lang.Class<T> imageType)
        Creates an instance of VisOdomDualTrackPnP.
        Parameters:
        configVO - Configuration
        imageType - Type of input image
        Returns:
        The new instance
      • stereoDualTrackerPnP

        public static <T extends boofcv.struct.image.ImageGray<T>,​Desc extends boofcv.struct.feature.TupleDesc> StereoVisualOdometry<T> stereoDualTrackerPnP​(ConfigVisOdomTrackPnP configVO,
                                                                                                                                                                   boofcv.abst.tracker.PointTracker<T> trackerLeft,
                                                                                                                                                                   boofcv.abst.tracker.PointTracker<T> trackerRight,
                                                                                                                                                                   ConfigStereoDualTrackPnP hack,
                                                                                                                                                                   java.lang.Class<T> imageType)
      • stereoQuadPnP

        public static <T extends boofcv.struct.image.ImageGray<T>,​Desc extends boofcv.struct.feature.TupleDesc> StereoVisualOdometry<T> stereoQuadPnP​(ConfigStereoQuadPnP config,
                                                                                                                                                            java.lang.Class<T> imageType)
        Creates a stereo visual odometry algorithm that uses the two most recent frames (4 images total) to estimate motion.
        See Also:
        VisOdomStereoQuadPnP
      • scaleInput

        public static <T extends boofcv.struct.image.ImageBase<T>> StereoVisualOdometry<T> scaleInput​(StereoVisualOdometry<T> vo,
                                                                                                      double scaleFactor)
        Wraps around a StereoVisualOdometry instance and will rescale the input images and adjust the cameras intrinsic parameters automatically. Rescaling input images is often an easy way to improve runtime performance with a minimal hit on pose accuracy.
        Type Parameters:
        T - Image type
        Parameters:
        vo - Visual odometry algorithm which is being wrapped
        scaleFactor - Scale factor that the image should be reduced by, Try 0.5 for half size.
        Returns:
        StereoVisualOdometry
      • scaleInput

        public static <T extends boofcv.struct.image.ImageBase<T>> MonocularPlaneVisualOdometry<T> scaleInput​(MonocularPlaneVisualOdometry<T> vo,
                                                                                                              double scaleFactor)
        Wraps around a MonocularPlaneVisualOdometry instance and will rescale the input images and adjust the cameras intrinsic parameters automatically. Rescaling input images is often an easy way to improve runtime performance with a minimal hit on pose accuracy.
        Type Parameters:
        T - Image type
        Parameters:
        vo - Visual odometry algorithm which is being wrapped
        scaleFactor - Scale factor that the image should be reduced by, Try 0.5 for half size.
        Returns:
        StereoVisualOdometry
      • depthDirect

        public static <Vis extends boofcv.struct.image.ImageGray<Vis>,​Depth extends boofcv.struct.image.ImageGray<Depth>> DepthVisualOdometry<boofcv.struct.image.Planar<Vis>,​Depth> depthDirect​(DepthSparse3D<Depth> sparse3D,
                                                                                                                                                                                                             boofcv.struct.image.ImageType<boofcv.struct.image.Planar<Vis>> visualType,
                                                                                                                                                                                                             java.lang.Class<Depth> depthType)