Package boofcv.abst.sfm.d3
Interface StereoVisualOdometry<T extends boofcv.struct.image.ImageBase<T>>
-
- All Superinterfaces:
org.ddogleg.struct.VerbosePrint,VisualOdometry<georegression.struct.se.Se3_F64>
- All Known Implementing Classes:
StereoVisualOdometryScaleInput,WrapVisOdomDualTrackPnP,WrapVisOdomMonoStereoDepthPnP,WrapVisOdomQuadPnP
public interface StereoVisualOdometry<T extends boofcv.struct.image.ImageBase<T>> extends VisualOdometry<georegression.struct.se.Se3_F64>
Stereo visual odometry algorithms that estimate the camera's ego-motion in Euclidean space using a pair of stereo images. Camera motion is estimated relative to the first frame in the left camera's point of view.
The following is a set of assumptions and behaviors that all implementations of this interface must follow:
- Stereo images must be captured simultaneously
- Cameras must have a global shutter
- Calibration parameters can be changed at any time, but must be set at least once before processing an image.
- If process returns false then the motion could not be estimated and isFault() should be checked
- If isFault() is true then the reset() should be called since it can't estimate motion any more
- reset() puts back into its initial state
Optional interfaces are provided for accessing internal features.
-
-
Field Summary
-
Fields inherited from interface boofcv.abst.sfm.d3.VisualOdometry
VERBOSE_RUNTIME, VERBOSE_TRACKING
-
-
Method Summary
All Methods Instance Methods Abstract Methods Modifier and Type Method Description boofcv.struct.image.ImageType<T>getImageType()Type of input images it can process.booleanprocess(T leftImage, T rightImage)Process the new image and update the motion estimate.voidsetCalibration(boofcv.struct.calib.StereoParameters parameters)Specifies intrinsic and extrinsic parameters for the stereo camera system.-
Methods inherited from interface boofcv.abst.sfm.d3.VisualOdometry
getCameraToWorld, getFrameID, isFault, reset
-
-
-
-
Method Detail
-
setCalibration
void setCalibration(boofcv.struct.calib.StereoParameters parameters)
Specifies intrinsic and extrinsic parameters for the stereo camera system. Can be called at any time, but must be called at least once beforeprocess(T, T)can be called.- Parameters:
parameters- stereo calibration
-
process
boolean process(T leftImage, T rightImage)
Process the new image and update the motion estimate. The return value must be checked to see if the estimate was actually updated. If false is returned thenVisualOdometry.isFault()also needs to be checked to see if the pose estimate has been reset.- Returns:
- true if the motion estimate has been updated and false if not
-
getImageType
boofcv.struct.image.ImageType<T> getImageType()
Type of input images it can process.- Returns:
- The image type
-
-