public class VisOdomQuadPnP<T extends boofcv.struct.image.ImageSingleBand,TD extends boofcv.struct.feature.TupleDesc>
extends java.lang.Object
PnP type algorithm.
Motion is estimated using PNP algorithms. These require that each image feature as its 3D coordinate estimated.
After a feature is associated between a stereo pair its 3D location is also estimated using triangulation. Iterative
refinement can then be applied after motion has been estimated.
Inside the code each camera is some times referred to by number. 0 = left camera previous frame. 1 = right
camera previous frame. 2 = left camera current frame. 3 = right camera current frame.
Estimated motion is relative to left camera.| Modifier and Type | Class and Description |
|---|---|
static class |
VisOdomQuadPnP.ImageInfo<TD extends boofcv.struct.feature.TupleDesc>
Storage for detected features inside an image
|
static class |
VisOdomQuadPnP.QuadView
3D coordinate of the feature and its observed location in each image
|
static class |
VisOdomQuadPnP.SetMatches
Correspondences between images
|
| Constructor and Description |
|---|
VisOdomQuadPnP(boofcv.abst.feature.detdesc.DetectDescribeMulti<T,TD> detector,
boofcv.abst.feature.associate.AssociateDescription2D<TD> assocSame,
boofcv.abst.feature.associate.AssociateDescription2D<TD> assocL2R,
boofcv.abst.geo.TriangulateTwoViewsCalibrated triangulate,
org.ddogleg.fitting.modelset.ModelMatcher<georegression.struct.se.Se3_F64,Stereo2D3D> matcher,
org.ddogleg.fitting.modelset.ModelFitter<georegression.struct.se.Se3_F64,Stereo2D3D> modelRefiner)
Specifies internal algorithms
|
| Modifier and Type | Method and Description |
|---|---|
georegression.struct.se.Se3_F64 |
getLeftToWorld() |
org.ddogleg.fitting.modelset.ModelMatcher<georegression.struct.se.Se3_F64,Stereo2D3D> |
getMatcher() |
org.ddogleg.struct.FastQueue<VisOdomQuadPnP.QuadView> |
getQuadViews() |
boolean |
process(T left,
T right)
Estimates camera egomotion from the stereo pair
|
void |
reset()
Resets the algorithm into its original state
|
void |
setCalibration(boofcv.struct.calib.StereoParameters param) |
public VisOdomQuadPnP(boofcv.abst.feature.detdesc.DetectDescribeMulti<T,TD> detector, boofcv.abst.feature.associate.AssociateDescription2D<TD> assocSame, boofcv.abst.feature.associate.AssociateDescription2D<TD> assocL2R, boofcv.abst.geo.TriangulateTwoViewsCalibrated triangulate, org.ddogleg.fitting.modelset.ModelMatcher<georegression.struct.se.Se3_F64,Stereo2D3D> matcher, org.ddogleg.fitting.modelset.ModelFitter<georegression.struct.se.Se3_F64,Stereo2D3D> modelRefiner)
detector - Estimates image featuresassocSame - Association algorithm used for left to left and right to rightassocL2R - Assocation algorithm used for left to righttriangulate - Used to estimate 3D location of a feature using stereo correspondencematcher - Robust model estimation. Often RANSACmodelRefiner - Non-linear refinement of motion estimationpublic void setCalibration(boofcv.struct.calib.StereoParameters param)
public void reset()
public boolean process(T left, T right)
left - Image from left cameraright - Image from right camerapublic org.ddogleg.fitting.modelset.ModelMatcher<georegression.struct.se.Se3_F64,Stereo2D3D> getMatcher()
public org.ddogleg.struct.FastQueue<VisOdomQuadPnP.QuadView> getQuadViews()
public georegression.struct.se.Se3_F64 getLeftToWorld()