Vis - Visual camera sensorDepth - Depth camera sensorpublic interface DepthVisualOdometry<Vis extends boofcv.struct.image.ImageBase,Depth extends boofcv.struct.image.ImageSingleBand> extends VisualOdometry<georegression.struct.se.Se3_F64>
Visual odometry that estimate the camera's ego-motion in Euclidean space using a camera image and a depth image. 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 |
|---|---|
java.lang.Class<Depth> |
getDepthType()
Type of depth images it can process.
|
boofcv.struct.image.ImageType<Vis> |
getVisualType()
Type of visual images it can process.
|
boolean |
process(Vis visual,
Depth depth)
Process the new image and update the motion estimate.
|
void |
setCalibration(boofcv.struct.calib.IntrinsicParameters paramVisual,
boofcv.struct.distort.PixelTransform_F32 visToDepth)
Specifies the intrinsic parameters for the visual camera and the transform from visual to depth pixels.
|
getCameraToWorld, isFault, resetvoid setCalibration(boofcv.struct.calib.IntrinsicParameters paramVisual,
boofcv.struct.distort.PixelTransform_F32 visToDepth)
paramVisual - Intrinsic parameters for visual cameravisToDepth - Transform from visual camera pixels into depth camera pixelsboolean process(Vis visual, Depth depth)
VisualOdometry.isFault()
also needs to be checked to see if the pose estimate has been reset.visual - Image from visual cameradepth - Image from depth sensorboofcv.struct.image.ImageType<Vis> getVisualType()
java.lang.Class<Depth> getDepthType()