public class FactoryVisualOdometry
extends java.lang.Object
| Constructor and Description |
|---|
FactoryVisualOdometry() |
| Modifier and Type | Method and Description |
|---|---|
static <Vis extends boofcv.struct.image.ImageSingleBand,Depth extends boofcv.struct.image.ImageSingleBand> |
depthDepthPnP(double inlierPixelTol,
int thresholdAdd,
int thresholdRetire,
int ransacIterations,
int refineIterations,
boolean doublePass,
DepthSparse3D<Depth> sparseDepth,
boofcv.abst.feature.tracker.PointTrackerTwoPass<Vis> tracker,
java.lang.Class<Vis> visualType,
java.lang.Class<Depth> depthType)
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.
|
static <T extends boofcv.struct.image.ImageSingleBand> |
monoPlaneInfinity(int thresholdAdd,
int thresholdRetire,
double inlierPixelTol,
int ransacIterations,
boofcv.abst.feature.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.ImageSingleBand> |
monoPlaneOverhead(double cellSize,
double maxCellsPerPixel,
double mapHeightFraction,
double inlierGroundTol,
int ransacIterations,
int thresholdRetire,
int absoluteMinimumTracks,
double respawnTrackFraction,
double respawnCoverageFraction,
boofcv.abst.feature.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> |
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> |
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.ImageSingleBand> |
stereoDepth(double inlierPixelTol,
int thresholdAdd,
int thresholdRetire,
int ransacIterations,
int refineIterations,
boolean doublePass,
boofcv.abst.feature.disparity.StereoDisparitySparse<T> sparseDisparity,
boofcv.abst.feature.tracker.PointTrackerTwoPass<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.ImageSingleBand,Desc extends boofcv.struct.feature.TupleDesc> |
stereoDualTrackerPnP(int thresholdAdd,
int thresholdRetire,
double inlierPixelTol,
double epipolarPixelTol,
int ransacIterations,
int refineIterations,
boofcv.abst.feature.tracker.PointTracker<T> trackerLeft,
boofcv.abst.feature.tracker.PointTracker<T> trackerRight,
boofcv.abst.feature.describe.DescribeRegionPoint<T,Desc> descriptor,
java.lang.Class<T> imageType)
Creates a stereo visual odometry algorithm that independently tracks features in left and right camera.
|
static <T extends boofcv.struct.image.ImageSingleBand,Desc extends boofcv.struct.feature.TupleDesc> |
stereoQuadPnP(double inlierPixelTol,
double epipolarPixelTol,
double maxDistanceF2F,
double maxAssociationError,
int ransacIterations,
int refineIterations,
boofcv.abst.feature.detdesc.DetectDescribeMulti<T,Desc> detector,
java.lang.Class<T> imageType)
Stereo visual odometry which uses the two most recent stereo observations (total of four views) to estimate
motion.
|
public static <T extends boofcv.struct.image.ImageSingleBand> MonocularPlaneVisualOdometry<T> monoPlaneInfinity(int thresholdAdd, int thresholdRetire, double inlierPixelTol, int ransacIterations, boofcv.abst.feature.tracker.PointTracker<T> tracker, boofcv.struct.image.ImageType<T> imageType)
T - 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 2inlierPixelTol - Threshold used to determine inliers in pixels. Try 1.5ransacIterations - Number of RANSAC iterations. Try 200tracker - Image feature trackerimageType - Type of input image it processesVisOdomMonoPlaneInfinitypublic static <T extends boofcv.struct.image.ImageSingleBand> MonocularPlaneVisualOdometry<T> monoPlaneOverhead(double cellSize, double maxCellsPerPixel, double mapHeightFraction, double inlierGroundTol, int ransacIterations, int thresholdRetire, int absoluteMinimumTracks, double respawnTrackFraction, double respawnCoverageFraction, boofcv.abst.feature.tracker.PointTracker<T> tracker, boofcv.struct.image.ImageType<T> imageType)
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 processedVisOdomMonoOverheadMotion2Dpublic static <T extends boofcv.struct.image.ImageSingleBand> StereoVisualOdometry<T> stereoDepth(double inlierPixelTol, int thresholdAdd, int thresholdRetire, int ransacIterations, int refineIterations, boolean doublePass, boofcv.abst.feature.disparity.StereoDisparitySparse<T> sparseDisparity, boofcv.abst.feature.tracker.PointTrackerTwoPass<T> tracker, java.lang.Class<T> imageType)
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 2sparseDisparity - Estimates the 3D location of featuresimageType - Type of image being processed.VisOdomPixelDepthPnPpublic static <Vis extends boofcv.struct.image.ImageSingleBand,Depth extends boofcv.struct.image.ImageSingleBand> DepthVisualOdometry<Vis,Depth> depthDepthPnP(double inlierPixelTol, int thresholdAdd, int thresholdRetire, int ransacIterations, int refineIterations, boolean doublePass, DepthSparse3D<Depth> sparseDepth, boofcv.abst.feature.tracker.PointTrackerTwoPass<Vis> tracker, java.lang.Class<Vis> visualType, java.lang.Class<Depth> depthType)
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 2sparseDepth - Extracts depth of pixels from a depth sensor.visualType - Type of visual image being processed.depthType - Type of depth image being processed.VisOdomPixelDepthPnPpublic static <T extends boofcv.struct.image.ImageSingleBand,Desc extends boofcv.struct.feature.TupleDesc> StereoVisualOdometry<T> stereoDualTrackerPnP(int thresholdAdd, int thresholdRetire, double inlierPixelTol, double epipolarPixelTol, int ransacIterations, int refineIterations, boofcv.abst.feature.tracker.PointTracker<T> trackerLeft, boofcv.abst.feature.tracker.PointTracker<T> trackerRight, boofcv.abst.feature.describe.DescribeRegionPoint<T,Desc> descriptor, java.lang.Class<T> imageType)
thresholdAdd - When the number of inliers is below this number new features are detectedthresholdRetire - When a feature has not been in the inlier list for this many ticks it is droppedinlierPixelTol - Tolerance in pixels for defining an inlier during robust model matching. Typically 1.5epipolarPixelTol - Tolerance in pixels for enforcing the epipolar constraintransacIterations - Number of iterations performed by RANSAC. Try 300 or more.refineIterations - Number of iterations done during non-linear optimization. Try 50 or more.trackerLeft - Tracker used for left cameratrackerRight - Tracker used for right cameraimageType - Type of image being processedVisOdomDualTrackPnPpublic static <T extends boofcv.struct.image.ImageSingleBand,Desc extends boofcv.struct.feature.TupleDesc> StereoVisualOdometry<T> stereoQuadPnP(double inlierPixelTol, double epipolarPixelTol, double maxDistanceF2F, double maxAssociationError, int ransacIterations, int refineIterations, boofcv.abst.feature.detdesc.DetectDescribeMulti<T,Desc> detector, java.lang.Class<T> imageType)
VisOdomQuadPnPpublic static <T extends boofcv.struct.image.ImageBase> StereoVisualOdometry<T> scaleInput(StereoVisualOdometry<T> vo, double scaleFactor)
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.T - Image typevo - Visual odometry algorithm which is being wrappedscaleFactor - Scale factor that the image should be reduced by, Try 0.5 for half size.public static <T extends boofcv.struct.image.ImageBase> MonocularPlaneVisualOdometry<T> scaleInput(MonocularPlaneVisualOdometry<T> vo, double scaleFactor)
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.T - Image typevo - Visual odometry algorithm which is being wrappedscaleFactor - Scale factor that the image should be reduced by, Try 0.5 for half size.