Package boofcv.factory.sfm
Class FactoryVisualOdometry
java.lang.Object
boofcv.factory.sfm.FactoryVisualOdometry
Factory for creating visual odometry algorithms.
-
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionstatic <Vis extends ImageGray<Vis>,
Depth extends ImageGray<Depth>>
DepthVisualOdometry<Planar<Vis>,Depth> depthDirect
(DepthSparse3D<Depth> sparse3D, ImageType<Planar<Vis>> visualType, Class<Depth> depthType) static <T extends ImageGray<T>>
MonocularPlaneVisualOdometry<T>monoPlaneInfinity
(@Nullable ConfigPlanarTrackPnP config, Class<T> imageType) Creates monocular visual odometry which relies on the ground being a flat planestatic <T extends ImageGray<T>>
MonocularPlaneVisualOdometry<T>monoPlaneOverhead
(double cellSize, double maxCellsPerPixel, double mapHeightFraction, double inlierGroundTol, int ransacIterations, int thresholdRetire, int absoluteMinimumTracks, double respawnTrackFraction, double respawnCoverageFraction, PointTracker<T> tracker, ImageType<T> imageType) Monocular plane based visual odometry algorithm which creates a synthetic overhead view and tracks image features inside this synthetic view.static <Vis extends ImageGray<Vis>,
Depth extends ImageGray<Depth>>
DepthVisualOdometry<Vis,Depth> rgbDepthPnP
(ConfigRgbDepthTrackPnP config, Class<Vis> visualType, Class<Depth> depthType) static <Vis extends ImageGray<Vis>,
Depth extends ImageGray<Depth>>
DepthVisualOdometry<Vis,Depth> rgbDepthPnP
(ConfigVisOdomTrackPnP configVO, DepthSparse3D<Depth> sparseDepth, PointTracker<Vis> tracker, Class<Vis> visualType, Class<Depth> depthType) static <T extends ImageBase<T>>
MonocularPlaneVisualOdometry<T>scaleInput
(MonocularPlaneVisualOdometry<T> vo, double scaleFactor) Wraps around aMonocularPlaneVisualOdometry
instance and will rescale the input images and adjust the cameras intrinsic parameters automatically.static <T extends ImageBase<T>>
StereoVisualOdometry<T>scaleInput
(StereoVisualOdometry<T> vo, double scaleFactor) Wraps around aStereoVisualOdometry
instance and will rescale the input images and adjust the cameras intrinsic parameters automatically.static <T extends ImageGray<T>>
StereoVisualOdometry<T>stereoDualTrackerPnP
(@Nullable ConfigStereoDualTrackPnP configVO, Class<T> imageType) Creates an instance ofVisOdomDualTrackPnP
.static <T extends ImageGray<T>,
Desc extends TupleDesc<Desc>>
StereoVisualOdometry<T>stereoDualTrackerPnP
(ConfigVisOdomTrackPnP configVO, PointTracker<T> trackerLeft, PointTracker<T> trackerRight, ConfigStereoDualTrackPnP hack, Class<T> imageType) static <T extends ImageGray<T>>
StereoVisualOdometry<T>stereoMonoPnP
(@Nullable ConfigStereoMonoTrackPnP config, 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 ImageGray<T>>
StereoVisualOdometry<T>stereoMonoPnP
(@Nullable ConfigVisOdomTrackPnP configVO, StereoDisparitySparse<T> sparseDisparity, PointTracker<T> tracker, 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 ImageGray<T>,
Desc extends TupleDesc<Desc>>
StereoVisualOdometry<T>stereoQuadPnP
(ConfigStereoQuadPnP config, Class<T> imageType) Creates a stereo visual odometry algorithm that uses the two most recent frames (4 images total) to estimate motion.
-
Constructor Details
-
FactoryVisualOdometry
public FactoryVisualOdometry()
-
-
Method Details
-
monoPlaneInfinity
public static <T extends ImageGray<T>> MonocularPlaneVisualOdometry<T> monoPlaneInfinity(@Nullable @Nullable ConfigPlanarTrackPnP config, Class<T> imageType) Creates monocular visual odometry which relies on the ground being a flat plane -
monoPlaneOverhead
public static <T extends ImageGray<T>> MonocularPlaneVisualOdometry<T> monoPlaneOverhead(double cellSize, double maxCellsPerPixel, double mapHeightFraction, double inlierGroundTol, int ransacIterations, int thresholdRetire, int absoluteMinimumTracks, double respawnTrackFraction, double respawnCoverageFraction, PointTracker<T> tracker, 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 unitsmaxCellsPerPixel
- (Overhead) Specifies the minimum resolution. Higher values allow lower resolutions. Try 20mapHeightFraction
- (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 pixelsransacIterations
- (RANSAC) Number of iterations used when estimating motionthresholdRetire
- (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 numberrespawnTrackFraction
- (2D Motion) Spawn tracks if the number of tracks has dropped below this fraction of the original numberrespawnCoverageFraction
- (2D Motion) Spawn tracks if the total coverage drops below this relative fractiontracker
- Image feature trackerimageType
- Type of image being processed- Returns:
- MonocularPlaneVisualOdometry
- See Also:
-
stereoMonoPnP
public static <T extends ImageGray<T>> StereoVisualOdometry<T> stereoMonoPnP(@Nullable @Nullable ConfigStereoMonoTrackPnP config, 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.- Returns:
- StereoVisualOdometry
- See Also:
-
stereoMonoPnP
public static <T extends ImageGray<T>> StereoVisualOdometry<T> stereoMonoPnP(@Nullable @Nullable ConfigVisOdomTrackPnP configVO, StereoDisparitySparse<T> sparseDisparity, PointTracker<T> tracker, 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 odometrysparseDisparity
- Estimates the 3D location of featurestracker
- Image point feature tracker.imageType
- Type of image being processed.- Returns:
- StereoVisualOdometry
- See Also:
-
rgbDepthPnP
public static <Vis extends ImageGray<Vis>,Depth extends ImageGray<Depth>> DepthVisualOdometry<Vis,Depth> rgbDepthPnP(ConfigRgbDepthTrackPnP config, Class<Vis> visualType, Class<Depth> depthType) -
rgbDepthPnP
public static <Vis extends ImageGray<Vis>,Depth extends ImageGray<Depth>> DepthVisualOdometry<Vis,Depth> rgbDepthPnP(ConfigVisOdomTrackPnP configVO, DepthSparse3D<Depth> sparseDepth, PointTracker<Vis> tracker, Class<Vis> visualType, Class<Depth> depthType) -
stereoDualTrackerPnP
public static <T extends ImageGray<T>> StereoVisualOdometry<T> stereoDualTrackerPnP(@Nullable @Nullable ConfigStereoDualTrackPnP configVO, Class<T> imageType) Creates an instance ofVisOdomDualTrackPnP
.- Parameters:
configVO
- ConfigurationimageType
- Type of input image- Returns:
- The new instance
-
stereoDualTrackerPnP
public static <T extends ImageGray<T>,Desc extends TupleDesc<Desc>> StereoVisualOdometry<T> stereoDualTrackerPnP(ConfigVisOdomTrackPnP configVO, PointTracker<T> trackerLeft, PointTracker<T> trackerRight, ConfigStereoDualTrackPnP hack, Class<T> imageType) -
stereoQuadPnP
public static <T extends ImageGray<T>,Desc extends TupleDesc<Desc>> StereoVisualOdometry<T> stereoQuadPnP(ConfigStereoQuadPnP config, Class<T> imageType) Creates a stereo visual odometry algorithm that uses the two most recent frames (4 images total) to estimate motion.- See Also:
-
scaleInput
public static <T extends ImageBase<T>> StereoVisualOdometry<T> scaleInput(StereoVisualOdometry<T> vo, double scaleFactor) Wraps around aStereoVisualOdometry
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 wrappedscaleFactor
- Scale factor that the image should be reduced by, Try 0.5 for half size.- Returns:
- StereoVisualOdometry
-
scaleInput
public static <T extends ImageBase<T>> MonocularPlaneVisualOdometry<T> scaleInput(MonocularPlaneVisualOdometry<T> vo, double scaleFactor) Wraps around aMonocularPlaneVisualOdometry
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 wrappedscaleFactor
- Scale factor that the image should be reduced by, Try 0.5 for half size.- Returns:
- StereoVisualOdometry
-
depthDirect
public static <Vis extends ImageGray<Vis>,Depth extends ImageGray<Depth>> DepthVisualOdometry<Planar<Vis>,Depth> depthDirect(DepthSparse3D<Depth> sparse3D, ImageType<Planar<Vis>> visualType, Class<Depth> depthType)
-