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:
Optional interfaces are provided for accessing internal features.
| Modifier and Type | Method and Description |
|---|---|
boofcv.struct.image.ImageType<T> |
getImageType()
Type of input images it can process.
|
boolean |
process(T leftImage,
T rightImage)
Process the new image and update the motion estimate.
|
void |
setCalibration(boofcv.struct.calib.StereoParameters parameters)
Specifies intrinsic and extrinsic parameters for the stereo camera system.
|
getCameraToWorld, isFault, resetvoid setCalibration(boofcv.struct.calib.StereoParameters parameters)
process(T, T) can be called.parameters - stereo calibrationboolean process(T leftImage, T rightImage)
VisualOdometry.isFault()
also needs to be checked to see if the pose estimate has been reset.boofcv.struct.image.ImageType<T> getImageType()